diff --git a/ArduBoat/ArduBoat.cpp b/ArduBoat/ArduBoat.cpp index 9841cf6c17..bd0063b5ff 100644 --- a/ArduBoat/ArduBoat.cpp +++ b/ArduBoat/ArduBoat.cpp @@ -22,3 +22,4 @@ #include "APO_DefaultSetup.h" #include ; int main(void) {init();setup();for(;;) loop(); return 0; } +// vim:ts=4:sw=4:expandtab diff --git a/ArduBoat/ArduBoat.pde b/ArduBoat/ArduBoat.pde index cbe9a99c66..8cc21d430a 100644 --- a/ArduBoat/ArduBoat.pde +++ b/ArduBoat/ArduBoat.pde @@ -20,3 +20,4 @@ // ArduPilotOne Default Setup #include "APO_DefaultSetup.h" +// vim:ts=4:sw=4:expandtab diff --git a/ArduBoat/BoatGeneric.h b/ArduBoat/BoatGeneric.h index 46c4de4d4f..b79f2f5634 100644 --- a/ArduBoat/BoatGeneric.h +++ b/ArduBoat/BoatGeneric.h @@ -3,6 +3,7 @@ * * Created on: May 1, 2011 * Author: jgoppert + * */ #ifndef BOATGENERIC_H_ @@ -27,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3; #define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL // baud rates -static uint32_t debugBaud = 57600; -static uint32_t telemBaud = 57600; -static uint32_t gpsBaud = 38400; -static uint32_t hilBaud = 57600; +static const uint32_t debugBaud = 57600; +static const uint32_t telemBaud = 57600; +static const uint32_t gpsBaud = 38400; +static const uint32_t hilBaud = 57600; // optional sensors static const bool gpsEnabled = false; @@ -61,20 +62,26 @@ static const float loop2Rate = 1; // gcs slow static const float loop3Rate = 0.1; // gains -const float steeringP = 1.0; -const float steeringI = 0.0; -const float steeringD = 0.0; -const float steeringIMax = 0.0; -const float steeringYMax = 3.0; -const float steeringDFCut = 25; +static const float steeringP = 0.1; +static const float steeringI = 0.0; +static const float steeringD = 0.1; +static const float steeringIMax = 0.0; +static const float steeringYMax = 1; +static const float steeringDFCut = 25.0; -const float throttleP = 0.0; -const float throttleI = 0.0; -const float throttleD = 0.0; -const float throttleIMax = 0.0; -const float throttleYMax = 0.0; -const float throttleDFCut = 3.0; +static const float throttleP = 0.1; +static const float throttleI = 0.0; +static const float throttleD = 0.0; +static const float throttleIMax = 0.0; +static const float throttleYMax = 1; +static const float throttleDFCut = 0.0; + +// guidance +static const float velCmd = 5; +static const float xt = 10; +static const float xtLim = 90; #include "ControllerBoat.h" #endif /* BOATGENERIC_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/ArduBoat/ControllerBoat.h b/ArduBoat/ControllerBoat.h index c0ac2c7c6f..97ae1ec10e 100644 --- a/ArduBoat/ControllerBoat.h +++ b/ArduBoat/ControllerBoat.h @@ -13,113 +13,68 @@ namespace apo { class ControllerBoat: public AP_Controller { -private: - AP_Var_group _group; - AP_Uint8 _mode; - enum { - k_chMode = k_radioChannelsStart, k_chStr, k_chThr - }; - enum { - k_pidStr = k_controllersStart, k_pidThr - }; - enum { - CH_MODE = 0, CH_STR, CH_THR - }; - BlockPIDDfb pidStr; - BlockPID pidThr; public: - ControllerBoat(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal), - _group(k_cntrl, PSTR("CNTRL_")), - _mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")), - pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, - steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut), - pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP, - throttleI, throttleD, throttleIMax, throttleYMax, - throttleDFCut) { - _hal->debug->println_P(PSTR("initializing boat controller")); + ControllerBoat(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9), ch_mode), + pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, + steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut), + pidThrust(new AP_Var_group(k_pidThrust, PSTR("THR_")), 1, throttleP, + throttleI, throttleD, throttleIMax, throttleYMax, + throttleDFCut), _strCmd(0), _thrustCmd(0) + { + _hal->debug->println_P(PSTR("initializing boat controller")); - _hal->rc.push_back( - new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540, - 1900, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, - 1900, RC_MODE_INOUT, false)); - } - virtual MAV_MODE getMode() { - return (MAV_MODE) _mode.get(); - } - virtual void update(const float & dt) { + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 3, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThrust, PSTR("THR_"), APM_RC, 2, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + } - // check for heartbeat - if (_hal->heartBeatLost()) { - _mode = MAV_MODE_FAILSAFE; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n")); - return; - // if throttle less than 5% cut motor power - } else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) { - _mode = MAV_MODE_LOCKED; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_STANDBY); - return; - // if in live mode then set state to active - } else if (_hal->getMode() == MODE_LIVE) { - _hal->setState(MAV_STATE_ACTIVE); - // if in hardware in the loop (control) mode, set to hilsim - } else if (_hal->getMode() == MODE_HIL_CNTL) { - _hal->setState(MAV_STATE_HILSIM); - } +private: + // methdos + void manualLoop(const float dt) { + setAllRadioChannelsManually(); + _strCmd = _hal->rc[ch_str]->getRadioPosition(); + _thrustCmd = _hal->rc[ch_thrust]->getRadioPosition(); + } + void autoLoop(const float dt) { + _strCmd = pidStr.update(_guide->getHeadingError(), _nav->getYawRate(), dt); + _thrustCmd = pidThrust.update( + _guide->getGroundSpeedCommand() + - _nav->getGroundSpeed(), dt); + } + void setMotorsActive() { + // turn all motors off if below 0.1 throttle + if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) { + setAllRadioChannelsToNeutral(); + } else { + _hal->rc[ch_thrust]->setPosition(_thrustCmd); + _hal->rc[ch_str]->setPosition(_strCmd); + } + } - // read switch to set mode - if (_hal->rc[CH_MODE]->getRadioPosition() > 0) { - _mode = MAV_MODE_MANUAL; - } else { - _mode = MAV_MODE_AUTO; - } - - // manual mode - switch (_mode) { - - case MAV_MODE_MANUAL: { - setAllRadioChannelsManually(); - //_hal->debug->println("manual"); - break; - } - case MAV_MODE_AUTO: { - float headingError = _guide->getHeadingCommand() - - _nav->getYaw(); - if (headingError > 180 * deg2Rad) - headingError -= 360 * deg2Rad; - if (headingError < -180 * deg2Rad) - headingError += 360 * deg2Rad; - _hal->rc[CH_STR]->setPosition( - pidStr.update(headingError, _nav->getYawRate(), dt)); - _hal->rc[CH_THR]->setPosition( - pidThr.update( - _guide->getGroundSpeedCommand() - - _nav->getGroundSpeed(), dt)); - //_hal->debug->println("automode"); - break; - } - - default: { - setAllRadioChannelsToNeutral(); - _mode = MAV_MODE_FAILSAFE; - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("unknown controller mode\n")); - break; - } - - } - } + // attributes + enum { + ch_mode = 0, ch_str, ch_thrust + }; + enum { + k_chMode = k_radioChannelsStart, k_chStr, k_chThrust + }; + enum { + k_pidStr = k_controllersStart, k_pidThrust + }; + BlockPIDDfb pidStr; + BlockPID pidThrust; + float _strCmd, _thrustCmd; }; } // namespace apo #endif /* CONTROLLERBOAT_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 0847662c09..1bc096f9df 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -27,7 +27,6 @@ V_FRAME */ - # define CH7_OPTION CH7_DO_NOTHING /* CH7_DO_NOTHING @@ -52,8 +51,7 @@ //#define RATE_ROLL_I 0.18 //#define RATE_PITCH_I 0.18 - - +//#define MOTORS_JD880 // agmatthews USERHOOKS diff --git a/ArduCopter/GCS.h b/ArduCopter/GCS.h index 21aa40d7d1..5f999f6ca2 100644 --- a/ArduCopter/GCS.h +++ b/ArduCopter/GCS.h @@ -135,10 +135,14 @@ private: uint16_t _parameter_count; ///< cache of reportable parameters AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index - mavlink_channel_t chan; uint16_t packet_drops; +#if CLI_ENABLED == ENABLED + // this allows us to detect the user wanting the CLI to start + uint8_t crlf_count; +#endif + // waypoints uint16_t waypoint_request_i; // request index uint16_t waypoint_dest_sysid; // where to send requests @@ -150,7 +154,6 @@ private: uint32_t waypoint_timelast_receive; // milliseconds uint16_t waypoint_send_timeout; // milliseconds uint16_t waypoint_receive_timeout; // milliseconds - float junk; //used to return a junk value for interface // data stream rates AP_Var_group _group; diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 4730ea57f4..ce351f2987 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -8,6 +8,9 @@ static bool in_mavlink_delay; // messages don't block the CPU static mavlink_statustext_t pending_status; +// true when we have received at least 1 MAVLink packet +static bool mavlink_active; + // check if a message will fit in the payload space available #define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false @@ -539,8 +542,26 @@ GCS_MAVLINK::update(void) { uint8_t c = comm_receive_ch(chan); +#if CLI_ENABLED == ENABLED + /* allow CLI to be started by hitting enter 3 times, if no + heartbeat packets have been received */ + if (mavlink_active == false) { + if (c == '\n' || c == '\r') { + crlf_count++; + } else { + crlf_count = 0; + } + if (crlf_count == 3) { + run_cli(); + } + } +#endif + // Try to get a new message - if(mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg); + if (mavlink_parse_char(chan, c, &msg, &status)) { + mavlink_active = true; + handleMessage(&msg); + } } // Update packet drops counter diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 5796d6a5d8..f0b8e5ee2d 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -361,6 +361,19 @@ ////////////////////////////////////////////////////////////////////////////// // Attitude Control // + +// Extra motor values that are changed from time to time by jani @ jDrones as software +// and charachteristics changes. +#ifdef MOTORS_JD880 +# define STABILIZE_ROLL_P 3.6 +# define STABILIZE_ROLL_I 0.06 +# define STABILIZE_ROLL_IMAX 2.0 // degrees +# define STABILIZE_PITCH_P 3.6 +# define STABILIZE_PITCH_I 0.06 +# define STABILIZE_PITCH_IMAX 2.0 // degrees +#endif + +// Jasons default values that are good for smaller payload motors. #ifndef STABILIZE_ROLL_P # define STABILIZE_ROLL_P 4.6 #endif @@ -702,6 +715,11 @@ # define CLI_ENABLED ENABLED #endif +// use this to disable the CLI slider switch +#ifndef CLI_SLIDER_ENABLED +# define CLI_SLIDER_ENABLED ENABLED +#endif + // delay to prevent Xbee bricking, in milliseconds #ifndef MAVLINK_TELEMETRY_PORT_DELAY # define MAVLINK_TELEMETRY_PORT_DELAY 2000 diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 8580808fcb..1979ee328a 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -43,6 +43,14 @@ const struct Menu::command main_menu_commands[] PROGMEM = { // Create the top-level menu object. MENU(main_menu, THISFIRMWARE, main_menu_commands); +// the user wants the CLI. It never exits +static void run_cli(void) +{ + while (1) { + main_menu.run(); + } +} + #endif // CLI_ENABLED static void init_ardupilot() @@ -215,7 +223,7 @@ static void init_ardupilot() DataFlash.Init(); #endif -#if CLI_ENABLED == ENABLED +#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED // If the switch is in 'menu' mode, run the main menu. // // Since we can't be sure that the setup or test mode won't leave @@ -225,11 +233,10 @@ static void init_ardupilot() if (check_startup_for_CLI()) { digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED Serial.printf_P(PSTR("\nCLI:\n\n")); - for (;;) { - //Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n")); - main_menu.run(); - } + run_cli(); } +#else + Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n")); #endif // CLI_ENABLED if(g.esc_calibrate == 1){ diff --git a/ArduPlane/GCS.h b/ArduPlane/GCS.h index 21aa40d7d1..5f999f6ca2 100644 --- a/ArduPlane/GCS.h +++ b/ArduPlane/GCS.h @@ -135,10 +135,14 @@ private: uint16_t _parameter_count; ///< cache of reportable parameters AP_Var *_find_parameter(uint16_t index); ///< find a reportable parameter by index - mavlink_channel_t chan; uint16_t packet_drops; +#if CLI_ENABLED == ENABLED + // this allows us to detect the user wanting the CLI to start + uint8_t crlf_count; +#endif + // waypoints uint16_t waypoint_request_i; // request index uint16_t waypoint_dest_sysid; // where to send requests @@ -150,7 +154,6 @@ private: uint32_t waypoint_timelast_receive; // milliseconds uint16_t waypoint_send_timeout; // milliseconds uint16_t waypoint_receive_timeout; // milliseconds - float junk; //used to return a junk value for interface // data stream rates AP_Var_group _group; diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index e87af0945c..23a4d4b298 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Mavlink_compat.h" + // use this to prevent recursion during sensor init static bool in_mavlink_delay; @@ -7,6 +9,8 @@ static bool in_mavlink_delay; // messages don't block the CPU static mavlink_statustext_t pending_status; +// true when we have received at least 1 MAVLink packet +static bool mavlink_active; // check if a message will fit in the payload space available #define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false @@ -23,10 +27,85 @@ static mavlink_statustext_t pending_status; static NOINLINE void send_heartbeat(mavlink_channel_t chan) { +#ifdef MAVLINK10 + uint8_t base_mode = 0; + uint8_t system_status = MAV_STATE_ACTIVE; + + // we map the custom_mode to our internal mode plus 16, to lower + // the chance that a ground station will give us 0 and we + // interpret it as manual. This is necessary as the SET_MODE + // command has no way to indicate that the custom_mode is filled in + uint32_t custom_mode = control_mode + 16; + + // work out the base_mode. This value is almost completely useless + // for APM, but we calculate it as best we can so a generic + // MAVLink enabled ground station can work out something about + // what the MAV is up to. The actual bit values are highly + // ambiguous for most of the APM flight modes. In practice, you + // only get useful information from the custom_mode, which maps to + // the APM flight mode and has a well defined meaning in the + // ArduPlane documentation + switch (control_mode) { + case MANUAL: + base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + break; + case STABILIZE: + case FLY_BY_WIRE_A: + case FLY_BY_WIRE_B: + case FLY_BY_WIRE_C: + base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED; + break; + case AUTO: + case RTL: + case LOITER: + case GUIDED: + case CIRCLE: + base_mode = MAV_MODE_FLAG_GUIDED_ENABLED | + MAV_MODE_FLAG_STABILIZE_ENABLED; + // note that MAV_MODE_FLAG_AUTO_ENABLED does not match what + // APM does in any mode, as that is defined as "system finds its own goal + // positions", which APM does not currently do + break; + case INITIALISING: + system_status = MAV_STATE_CALIBRATING; + break; + } + + if (control_mode != MANUAL && control_mode != INITIALISING) { + // stabiliser of some form is enabled + base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED; + } + +#if ENABLE_STICK_MIXING==ENABLED + if (control_mode != INITIALISING) { + // all modes except INITIALISING have some form of manual + // override if stick mixing is enabled + base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + } +#endif + +#if HIL_MODE != HIL_MODE_DISABLED + base_mode |= MAV_MODE_FLAG_HIL_ENABLED; +#endif + + // we are armed if we are not initialising + if (control_mode != INITIALISING) { + base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; + } + + mavlink_msg_heartbeat_send( + chan, + MAV_TYPE_FIXED_WING, + MAV_AUTOPILOT_ARDUPILOTMEGA, + base_mode, + custom_mode, + system_status); +#else // MAVLINK10 mavlink_msg_heartbeat_send( chan, mavlink_system.type, MAV_AUTOPILOT_ARDUPILOTMEGA); +#endif // MAVLINK10 } static NOINLINE void send_attitude(mavlink_channel_t chan) @@ -45,6 +124,103 @@ static NOINLINE void send_attitude(mavlink_channel_t chan) static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops) { +#ifdef MAVLINK10 + uint32_t control_sensors_present = 0; + uint32_t control_sensors_enabled; + uint32_t control_sensors_health; + + // first what sensors/controllers we have + control_sensors_present |= (1<<0); // 3D gyro present + control_sensors_present |= (1<<1); // 3D accelerometer present + if (g.compass_enabled) { + control_sensors_present |= (1<<2); // compass present + } + control_sensors_present |= (1<<3); // absolute pressure sensor present + if (g_gps->fix) { + control_sensors_present |= (1<<5); // GPS present + } + control_sensors_present |= (1<<10); // 3D angular rate control + control_sensors_present |= (1<<11); // attitude stabilisation + control_sensors_present |= (1<<12); // yaw position + control_sensors_present |= (1<<13); // altitude control + control_sensors_present |= (1<<14); // X/Y position control + control_sensors_present |= (1<<15); // motor control + + // now what sensors/controllers are enabled + + // first the sensors + control_sensors_enabled = control_sensors_present & 0x1FF; + + // now the controllers + control_sensors_enabled = control_sensors_present & 0x1FF; + + switch (control_mode) { + case MANUAL: + break; + + case STABILIZE: + case FLY_BY_WIRE_A: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + break; + + case FLY_BY_WIRE_B: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + control_sensors_enabled |= (1<<15); // motor control + break; + + case FLY_BY_WIRE_C: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + control_sensors_enabled |= (1<<13); // altitude control + control_sensors_enabled |= (1<<15); // motor control + break; + + case AUTO: + case RTL: + case LOITER: + case GUIDED: + case CIRCLE: + control_sensors_enabled |= (1<<10); // 3D angular rate control + control_sensors_enabled |= (1<<11); // attitude stabilisation + control_sensors_enabled |= (1<<12); // yaw position + control_sensors_enabled |= (1<<13); // altitude control + control_sensors_enabled |= (1<<14); // X/Y position control + control_sensors_enabled |= (1<<15); // motor control + break; + + case INITIALISING: + break; + } + + // at the moment all sensors/controllers are assumed healthy + control_sensors_health = control_sensors_present; + + uint16_t battery_current = -1; + uint8_t battery_remaining = -1; + + if (current_total != 0 && g.pack_capacity != 0) { + battery_remaining = (100.0 * (g.pack_capacity - current_total) / g.pack_capacity); + } + if (current_total != 0) { + battery_current = current_amps * 100; + } + + mavlink_msg_sys_status_send( + chan, + control_sensors_present, + control_sensors_enabled, + control_sensors_health, + (uint16_t)(load * 1000), + battery_voltage * 1000, // mV + battery_current, // in 10mA units + battery_remaining, // in % + 0, // comm drops %, + 0, // comm drops in pkts, + 0, 0, 0, 0); + +#else // MAVLINK10 uint8_t mode = MAV_MODE_UNINIT; uint8_t nav_mode = MAV_NAV_VECTOR; @@ -96,6 +272,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack battery_voltage * 1000, battery_remaining, packet_drops); +#endif // MAVLINK10 } static void NOINLINE send_meminfo(mavlink_channel_t chan) @@ -107,6 +284,19 @@ static void NOINLINE send_meminfo(mavlink_channel_t chan) static void NOINLINE send_location(mavlink_channel_t chan) { Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now +#ifdef MAVLINK10 + mavlink_msg_global_position_int_send( + chan, + millis(), + current_loc.lat, // in 1E7 degrees + current_loc.lng, // in 1E7 degrees + g_gps->altitude*10, // millimeters above sea level + current_loc.alt * 10, // millimeters above ground + g_gps->ground_speed * rot.a.x, // X speed cm/s + g_gps->ground_speed * rot.b.x, // Y speed cm/s + g_gps->ground_speed * rot.c.x, + g_gps->ground_course); // course in 1/100 degree +#else // MAVLINK10 mavlink_msg_global_position_int_send( chan, current_loc.lat, @@ -115,6 +305,7 @@ static void NOINLINE send_location(mavlink_channel_t chan) g_gps->ground_speed * rot.a.x, g_gps->ground_speed * rot.b.x, g_gps->ground_speed * rot.c.x); +#endif // MAVLINK10 } static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) @@ -133,6 +324,28 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) static void NOINLINE send_gps_raw(mavlink_channel_t chan) { +#ifdef MAVLINK10 + uint8_t fix; + if (g_gps->status() == 2) { + fix = 3; + } else { + fix = 0; + } + + mavlink_msg_gps_raw_int_send( + chan, + micros(), + fix, + g_gps->latitude, // in 1E7 degrees + g_gps->longitude, // in 1E7 degrees + g_gps->altitude * 10, // in mm + g_gps->hdop, + 65535, + g_gps->ground_speed, // cm/s + g_gps->ground_course, // 1/100 degrees, + g_gps->num_sats); + +#else // MAVLINK10 mavlink_msg_gps_raw_send( chan, micros(), @@ -144,13 +357,31 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) 0.0, g_gps->ground_speed / 100.0, g_gps->ground_course / 100.0); +#endif // MAVLINK10 } static void NOINLINE send_servo_out(mavlink_channel_t chan) { const uint8_t rssi = 1; // normalized values scaled to -10000 to 10000 - // This is used for HIL. Do not change without discussing with HIL maintainers + // This is used for HIL. Do not change without discussing with + // HIL maintainers +#ifdef MAVLINK10 + mavlink_msg_rc_channels_scaled_send( + chan, + millis(), + 0, // port 0 + 10000 * g.channel_roll.norm_output(), + 10000 * g.channel_pitch.norm_output(), + 10000 * g.channel_throttle.norm_output(), + 10000 * g.channel_rudder.norm_output(), + 0, + 0, + 0, + 0, + rssi); + +#else // MAVLINK10 mavlink_msg_rc_channels_scaled_send( chan, 10000 * g.channel_roll.norm_output(), @@ -162,12 +393,29 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan) 0, 0, rssi); +#endif // MAVLINK10 } static void NOINLINE send_radio_in(mavlink_channel_t chan) { uint8_t rssi = 1; +#ifdef MAVLINK10 mavlink_msg_rc_channels_raw_send( + chan, + millis(), + 0, // port + g.channel_roll.radio_in, + g.channel_pitch.radio_in, + g.channel_throttle.radio_in, + g.channel_rudder.radio_in, + g.rc_5.radio_in, // XXX currently only 4 RC channels defined + g.rc_6.radio_in, + g.rc_7.radio_in, + g.rc_8.radio_in, + rssi); + +#else // MAVLINK10 + mavlink_msg_rc_channels_raw_send( chan, g.channel_roll.radio_in, g.channel_pitch.radio_in, @@ -178,10 +426,25 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan) g.rc_7.radio_in, g.rc_8.radio_in, rssi); +#endif // MAVLINK10 } static void NOINLINE send_radio_out(mavlink_channel_t chan) { +#ifdef MAVLINK10 + mavlink_msg_servo_output_raw_send( + chan, + micros(), + 0, // port + g.channel_roll.radio_out, + g.channel_pitch.radio_out, + g.channel_throttle.radio_out, + g.channel_rudder.radio_out, + g.rc_5.radio_out, // XXX currently only 4 RC channels defined + g.rc_6.radio_out, + g.rc_7.radio_out, + g.rc_8.radio_out); +#else // MAVLINK10 mavlink_msg_servo_output_raw_send( chan, g.channel_roll.radio_out, @@ -192,6 +455,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan) g.rc_6.radio_out, g.rc_7.radio_out, g.rc_8.radio_out); +#endif // MAVLINK10 } static void NOINLINE send_vfr_hud(mavlink_channel_t chan) @@ -325,7 +589,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id, break; case MSG_GPS_RAW: +#ifdef MAVLINK10 + CHECK_PAYLOAD_SIZE(GPS_RAW_INT); +#else CHECK_PAYLOAD_SIZE(GPS_RAW); +#endif send_gps_raw(chan); break; @@ -480,10 +748,11 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char mavlink_send_message(chan, MSG_STATUSTEXT, 0); } else { // send immediately - mavlink_msg_statustext_send( - chan, - severity, - (const int8_t*) str); +#ifdef MAVLINK10 + mavlink_msg_statustext_send(chan, severity, str); +#else + mavlink_msg_statustext_send(chan, severity, (const int8_t*) str); +#endif } } @@ -538,8 +807,26 @@ GCS_MAVLINK::update(void) { uint8_t c = comm_receive_ch(chan); +#if CLI_ENABLED == ENABLED + /* allow CLI to be started by hitting enter 3 times, if no + heartbeat packets have been received */ + if (mavlink_active == 0) { + if (c == '\n' || c == '\r') { + crlf_count++; + } else { + crlf_count = 0; + } + if (crlf_count == 3) { + run_cli(); + } + } +#endif + // Try to get a new message - if (mavlink_parse_char(chan, c, &msg, &status)) handleMessage(&msg); + if (mavlink_parse_char(chan, c, &msg, &status)) { + mavlink_active = 1; + handleMessage(&msg); + } } // Update packet drops counter @@ -721,6 +1008,68 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } +#ifdef MAVLINK10 + case MAVLINK_MSG_ID_COMMAND_LONG: + { + // decode + mavlink_command_long_t packet; + mavlink_msg_command_long_decode(msg, &packet); + if (mavlink_check_target(packet.target_system, packet.target_component)) break; + + uint8_t result; + + // do command + send_text(SEVERITY_LOW,PSTR("command received: ")); + + switch(packet.command) { + + case MAV_CMD_NAV_LOITER_UNLIM: + set_mode(LOITER); + result = MAV_RESULT_ACCEPTED; + break; + + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + set_mode(RTL); + result = MAV_RESULT_ACCEPTED; + break; + +#if 0 + // not implemented yet, but could implement some of them + case MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_NAV_ROI: + case MAV_CMD_NAV_PATHPLANNING: + break; +#endif + + + case MAV_CMD_PREFLIGHT_CALIBRATION: + if (packet.param1 == 1 || + packet.param2 == 1 || + packet.param3 == 1) { + startup_IMU_ground(); + } + if (packet.param4 == 1) { + trim_radio(); + } + result = MAV_RESULT_ACCEPTED; + break; + + + default: + result = MAV_RESULT_UNSUPPORTED; + break; + } + + mavlink_msg_command_ack_send( + chan, + packet.command, + result); + + break; + } + +#else // MAVLINK10 case MAVLINK_MSG_ID_ACTION: { // decode @@ -840,6 +1189,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } +#endif case MAVLINK_MSG_ID_SET_MODE: { @@ -847,6 +1197,29 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) mavlink_set_mode_t packet; mavlink_msg_set_mode_decode(msg, &packet); +#ifdef MAVLINK10 + // we ignore base_mode as there is no sane way to map + // from that bitmap to a APM flight mode. We rely on + // custom_mode instead. + // see comment on custom_mode above + int16_t adjusted_mode = packet.custom_mode - 16; + + switch (adjusted_mode) { + case MANUAL: + case CIRCLE: + case STABILIZE: + case FLY_BY_WIRE_A: + case FLY_BY_WIRE_B: + case FLY_BY_WIRE_C: + case AUTO: + case RTL: + case LOITER: + set_mode(adjusted_mode); + break; + } + +#else // MAVLINK10 + switch(packet.mode){ case MAV_MODE_MANUAL: @@ -876,8 +1249,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } +#endif + break; } +#ifndef MAVLINK10 case MAVLINK_MSG_ID_SET_NAV_MODE: { // decode @@ -887,6 +1263,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) mav_nav = packet.nav_mode; break; } +#endif // MAVLINK10 + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: { @@ -910,6 +1288,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } + // XXX read a WP from EEPROM and send it to the GCS case MAVLINK_MSG_ID_WAYPOINT_REQUEST: { @@ -1021,6 +1400,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } + case MAVLINK_MSG_ID_WAYPOINT_ACK: { // decode @@ -1056,13 +1436,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) if (mavlink_check_target(packet.target_system, packet.target_component)) break; // clear all waypoints - const uint8_t type = 0; // ok (0), error(1) g.waypoint_total.set_and_save(0); - // send acknowledgement 3 times to makes sure it is received - for (uint8_t i=0;i<3;i++) - mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, type); - + // note that we don't send multiple acks, as otherwise a + // GCS that is doing a clear followed by a set may see + // the additional ACKs as ACKs of the set operations + mavlink_msg_waypoint_ack_send(chan, msg->sysid, msg->compid, MAV_MISSION_ACCEPTED); break; } @@ -1116,6 +1495,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) { // decode mavlink_waypoint_t packet; + uint8_t result = MAV_MISSION_ACCEPTED; + mavlink_msg_waypoint_decode(msg, &packet); if (mavlink_check_target(packet.target_system,packet.target_component)) break; @@ -1134,6 +1515,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; } +#ifdef MAV_FRAME_LOCAL_NED + case MAV_FRAME_LOCAL_NED: // local (relative to home position) + { + tell_command.lat = 1.0e7*ToDeg(packet.x/ + (radius_of_earth*cos(ToRad(home.lat/1.0e7)))) + home.lat; + tell_command.lng = 1.0e7*ToDeg(packet.y/radius_of_earth) + home.lng; + tell_command.alt = -packet.z*1.0e2; + tell_command.options = MASK_OPTIONS_RELATIVE_ALT; + break; + } +#endif + +#ifdef MAV_FRAME_LOCAL case MAV_FRAME_LOCAL: // local (relative to home position) { tell_command.lat = 1.0e7*ToDeg(packet.x/ @@ -1143,6 +1537,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) tell_command.options = MASK_OPTIONS_RELATIVE_ALT; break; } +#endif + case MAV_FRAME_GLOBAL_RELATIVE_ALT: // absolute lat/lng, relative altitude { tell_command.lat = 1.0e7 * packet.x; // in as DD converted to * t7 @@ -1151,9 +1547,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) tell_command.options = MASK_OPTIONS_RELATIVE_ALT; // store altitude relative!! Always!! break; } + + default: + result = MAV_MISSION_UNSUPPORTED_FRAME; + break; } + + if (result != MAV_MISSION_ACCEPTED) goto mission_failed; + switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields + case MAV_CMD_NAV_WAYPOINT: + case MAV_CMD_NAV_LOITER_UNLIM: + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_LAND: + break; + case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_DO_SET_HOME: @@ -1193,8 +1602,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) tell_command.alt = packet.param2; tell_command.p1 = packet.param1; break; + + default: +#ifdef MAVLINK10 + result = MAV_MISSION_UNSUPPORTED; +#endif + break; } + if (result != MAV_MISSION_ACCEPTED) goto mission_failed; + if(packet.current == 2){ //current = 2 is a flag to tell us this is a "guided mode" waypoint and not for the mission guided_WP = tell_command; @@ -1217,24 +1634,29 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else { // Check if receiving waypoints (mission upload expected) - if (!waypoint_receiving) break; + if (!waypoint_receiving) { + result = MAV_MISSION_ERROR; + goto mission_failed; + } // check if this is the requested waypoint - if (packet.seq != waypoint_request_i) break; - set_wp_with_index(tell_command, packet.seq); + if (packet.seq != waypoint_request_i) { + result = MAV_MISSION_INVALID_SEQUENCE; + goto mission_failed; + } + + set_wp_with_index(tell_command, packet.seq); // update waypoint receiving state machine waypoint_timelast_receive = millis(); waypoint_request_i++; if (waypoint_request_i > (uint16_t)g.waypoint_total){ - uint8_t type = 0; // ok (0), error(1) - mavlink_msg_waypoint_ack_send( chan, msg->sysid, msg->compid, - type); + result); send_text(SEVERITY_LOW,PSTR("flight plan received")); waypoint_receiving = false; @@ -1243,6 +1665,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } } break; + + mission_failed: + // we are rejecting the mission/waypoint + mavlink_msg_waypoint_ack_send( + chan, + msg->sysid, + msg->compid, + result); + break; } case MAVLINK_MSG_ID_PARAM_SET: @@ -1280,10 +1711,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // handle variables with standard type IDs if (var_type == AP_Var::k_typeid_float) { ((AP_Float *)vp)->set_and_save(packet.param_value); - } else if (var_type == AP_Var::k_typeid_float16) { ((AP_Float16 *)vp)->set_and_save(packet.param_value); - } else if (var_type == AP_Var::k_typeid_int32) { if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition); @@ -1302,12 +1731,22 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // we send the value we actually set, which could be // different from the value sent, in case someone sent // a fractional value to an integer type +#ifdef MAVLINK10 + mavlink_msg_param_value_send( + chan, + key, + vp->cast_to_float(), + mav_var_type(vp->meta_type_id()), + _count_parameters(), + -1); // XXX we don't actually know what its index is... +#else // MAVLINK10 mavlink_msg_param_value_send( chan, (int8_t *)key, vp->cast_to_float(), _count_parameters(), - -1); // XXX we don't actually know what its index is... + -1); // XXX we don't actually know what its index is... +#endif // MAVLINK10 } break; @@ -1351,6 +1790,20 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) #if HIL_MODE != HIL_MODE_DISABLED // This is used both as a sensor and to pass the location // in HIL_ATTITUDE mode. +#ifdef MAVLINK10 + case MAVLINK_MSG_ID_GPS_RAW_INT: + { + // decode + mavlink_gps_raw_int_t packet; + mavlink_msg_gps_raw_int_decode(msg, &packet); + + // set gps hil sensor + g_gps->setHIL(packet.time_usec/1000.0, + packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3, + packet.vel*1.0e-2, packet.cog*1.0e-2, 0, 0); + break; + } +#else // MAVLINK10 case MAVLINK_MSG_ID_GPS_RAW: { // decode @@ -1362,6 +1815,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) packet.v,packet.hdg,0,0); break; } +#endif // MAVLINK10 // Is this resolved? - MAVLink protocol change..... case MAVLINK_MSG_ID_VFR_HUD: @@ -1505,12 +1959,22 @@ GCS_MAVLINK::queued_param_send() char param_name[ONBOARD_PARAM_NAME_LENGTH]; /// XXX HACK vp->copy_name(param_name, sizeof(param_name)); +#ifdef MAVLINK10 + mavlink_msg_param_value_send( + chan, + param_name, + value, + mav_var_type(vp->meta_type_id()), + _queued_parameter_count, + _queued_parameter_index); +#else // MAVLINK10 mavlink_msg_param_value_send( chan, (int8_t*)param_name, value, _queued_parameter_count, _queued_parameter_index); +#endif // MAVLINK10 _queued_parameter_index++; } diff --git a/ArduPlane/Mavlink_compat.h b/ArduPlane/Mavlink_compat.h new file mode 100644 index 0000000000..a9884bf780 --- /dev/null +++ b/ArduPlane/Mavlink_compat.h @@ -0,0 +1,81 @@ +/* + compatibility header during transition to MAVLink 1.0 + */ + +#ifdef MAVLINK10 +// in MAVLink 1.0 'waypoint' becomes 'mission'. We can remove these +// mappings once we are not trying to support both protocols + +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT MAVLINK_MSG_ID_MISSION_CURRENT +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN MAVLINK_MSG_ID_MISSION_CURRENT_LEN +#define mavlink_msg_waypoint_current_send mavlink_msg_mission_current_send +#define mavlink_msg_waypoint_current_decode mavlink_msg_mission_current_decode + +#define MAVLINK_MSG_ID_WAYPOINT_COUNT MAVLINK_MSG_ID_MISSION_COUNT +#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN MAVLINK_MSG_ID_MISSION_COUNT_LEN +#define mavlink_msg_waypoint_count_send mavlink_msg_mission_count_send +#define mavlink_msg_waypoint_count_decode mavlink_msg_mission_count_decode +#define mavlink_waypoint_count_t mavlink_mission_count_t + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST MAVLINK_MSG_ID_MISSION_REQUEST +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LEN +#define mavlink_msg_waypoint_request_send mavlink_msg_mission_request_send +#define mavlink_msg_waypoint_request_decode mavlink_msg_mission_request_decode +#define mavlink_waypoint_request_t mavlink_mission_request_t + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST MAVLINK_MSG_ID_MISSION_REQUEST_LIST +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN +#define mavlink_msg_waypoint_request_list_send mavlink_msg_mission_request_list_send +#define mavlink_msg_waypoint_request_list_decode mavlink_msg_mission_request_list_decode +#define mavlink_waypoint_request_list_t mavlink_mission_request_list_t + +#define MAVLINK_MSG_ID_WAYPOINT MAVLINK_MSG_ID_MISSION_ITEM +#define MAVLINK_MSG_ID_WAYPOINT_LEN MAVLINK_MSG_ID_MISSION_ITEM_LEN +#define mavlink_msg_waypoint_send mavlink_msg_mission_item_send +#define mavlink_msg_waypoint_decode mavlink_msg_mission_item_decode +#define mavlink_waypoint_t mavlink_mission_item_t + +#define MAVLINK_MSG_ID_WAYPOINT_ACK MAVLINK_MSG_ID_MISSION_ACK +#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN MAVLINK_MSG_ID_MISSION_ACK_LEN +#define mavlink_msg_waypoint_ack_send mavlink_msg_mission_ack_send +#define mavlink_msg_waypoint_ack_decode mavlink_msg_mission_ack_decode +#define mavlink_waypoint_ack_t mavlink_mission_ack_t + +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL MAVLINK_MSG_ID_MISSION_CLEAR_ALL +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN +#define mavlink_msg_waypoint_clear_all_send mavlink_msg_mission_clear_all_send +#define mavlink_msg_waypoint_clear_all_decode mavlink_msg_mission_clear_all_decode +#define mavlink_waypoint_clear_all_t mavlink_mission_clear_all_t + +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT MAVLINK_MSG_ID_MISSION_SET_CURRENT +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN +#define mavlink_msg_waypoint_set_current_send mavlink_msg_mission_set_current_send +#define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode +#define mavlink_waypoint_set_current_t mavlink_mission_set_current_t + +static uint8_t mav_var_type(AP_Meta_class::Type_id t) +{ + if (t == AP_Var::k_typeid_int8) { + return MAV_VAR_INT8; + } + if (t == AP_Var::k_typeid_int16) { + return MAV_VAR_INT16; + } + if (t == AP_Var::k_typeid_int32) { + return MAV_VAR_INT32; + } + // treat any others as float + return MAV_VAR_FLOAT; +} + +#define MAV_FIXED_WING MAV_TYPE_FIXED_WING + +#else + +#define MAV_MISSION_ACCEPTED 0 +#define MAV_MISSION_UNSUPPORTED 1 +#define MAV_MISSION_UNSUPPORTED_FRAME 1 +#define MAV_MISSION_ERROR 1 +#define MAV_MISSION_INVALID_SEQUENCE 1 + +#endif diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 43964df9c6..692c016136 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -662,6 +662,11 @@ # define CLI_ENABLED ENABLED #endif +// use this to disable the CLI slider switch +#ifndef CLI_SLIDER_ENABLED +# define CLI_SLIDER_ENABLED ENABLED +#endif + // delay to prevent Xbee bricking, in milliseconds #ifndef MAVLINK_TELEMETRY_PORT_DELAY # define MAVLINK_TELEMETRY_PORT_DELAY 2000 diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index e0a73e7b92..0e4f0aebb0 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -43,6 +43,14 @@ static const struct Menu::command main_menu_commands[] PROGMEM = { // Create the top-level menu object. MENU(main_menu, THISFIRMWARE, main_menu_commands); +// the user wants the CLI. It never exits +static void run_cli(void) +{ + while (1) { + main_menu.run(); + } +} + #endif // CLI_ENABLED static void init_ardupilot() @@ -185,7 +193,7 @@ static void init_ardupilot() // the system in an odd state, we don't let the user exit the top // menu; they must reset in order to fly. // -#if CLI_ENABLED == ENABLED +#if CLI_ENABLED == ENABLED && CLI_SLIDER_ENABLED == ENABLED if (digitalRead(SLIDE_SWITCH_PIN) == 0) { digitalWrite(A_LED_PIN,HIGH); // turn on setup-mode LED Serial.printf_P(PSTR("\n" @@ -194,14 +202,13 @@ static void init_ardupilot() "If using the Arduino Serial Monitor, ensure Line Ending is set to Carriage Return.\n" "Type 'help' to list commands, 'exit' to leave a submenu.\n" "Visit the 'setup' menu for first-time configuration.\n")); - for (;;) { - Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n")); - main_menu.run(); - } + Serial.println_P(PSTR("\nMove the slide switch and reset to FLY.\n")); + run_cli(); } +#else + Serial.printf_P(PSTR("\nPress ENTER 3 times to start interactive setup\n\n")); #endif // CLI_ENABLED - if(g.log_bitmask != 0){ // TODO - Here we will check on the length of the last log // We don't want to create a bunch of little logs due to powering on and off diff --git a/ArduRover/ArduRover.cpp b/ArduRover/ArduRover.cpp index 4d4a29a733..3341f3e598 100644 --- a/ArduRover/ArduRover.cpp +++ b/ArduRover/ArduRover.cpp @@ -23,3 +23,4 @@ #include "APO_DefaultSetup.h" #include ; int main(void) {init();setup();for(;;) loop(); return 0; } +// vim:ts=4:sw=4:expandtab diff --git a/ArduRover/ArduRover.pde b/ArduRover/ArduRover.pde index 14846ca904..baa0d19654 100644 --- a/ArduRover/ArduRover.pde +++ b/ArduRover/ArduRover.pde @@ -18,6 +18,7 @@ // Vehicle Configuration #include "CarStampede.h" +//#include "TankGeneric.h" // ArduPilotOne Default Setup #include "APO_DefaultSetup.h" diff --git a/ArduRover/CarStampede.h b/ArduRover/CarStampede.h index dc67d6730a..0e319436de 100644 --- a/ArduRover/CarStampede.h +++ b/ArduRover/CarStampede.h @@ -28,10 +28,10 @@ static const uint8_t heartBeatTimeout = 3; #define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL // baud rates -static uint32_t debugBaud = 57600; -static uint32_t telemBaud = 57600; -static uint32_t gpsBaud = 38400; -static uint32_t hilBaud = 57600; +static const uint32_t debugBaud = 57600; +static const uint32_t telemBaud = 57600; +static const uint32_t gpsBaud = 38400; +static const uint32_t hilBaud = 57600; // optional sensors static const bool gpsEnabled = false; @@ -41,7 +41,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD // compass orientation: See AP_Compass_HMC5843.h for possible values // battery monitoring -static const bool batteryMonitorEnabled = true; +static const bool batteryMonitorEnabled = false; static const uint8_t batteryPin = 0; static const float batteryVoltageDivRatio = 6; static const float batteryMinVolt = 10.0; @@ -62,20 +62,26 @@ static const float loop2Rate = 1; // gcs slow static const float loop3Rate = 0.1; // gains -static const float steeringP = 1.0; +static const float steeringP = 0.1; static const float steeringI = 0.0; -static const float steeringD = 0.0; +static const float steeringD = 0.1; static const float steeringIMax = 0.0; -static const float steeringYMax = 3.0; -static const float steeringDFCut = 25; +static const float steeringYMax = 1; +static const float steeringDFCut = 25.0; -static const float throttleP = 0.0; +static const float throttleP = 0.1; static const float throttleI = 0.0; static const float throttleD = 0.0; static const float throttleIMax = 0.0; -static const float throttleYMax = 0.0; -static const float throttleDFCut = 3.0; +static const float throttleYMax = 1; +static const float throttleDFCut = 0.0; + +// guidance +static const float velCmd = 5; +static const float xt = 10; +static const float xtLim = 90; #include "ControllerCar.h" #endif /* CARSTAMPEDE_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/ArduRover/ControllerCar.h b/ArduRover/ControllerCar.h index 686ea64787..c1951cf786 100644 --- a/ArduRover/ControllerCar.h +++ b/ArduRover/ControllerCar.h @@ -13,113 +13,69 @@ namespace apo { class ControllerCar: public AP_Controller { -private: - AP_Var_group _group; - AP_Uint8 _mode; - enum { - k_chMode = k_radioChannelsStart, k_chStr, k_chThr - }; - enum { - k_pidStr = k_controllersStart, k_pidThr - }; - enum { - CH_MODE = 0, CH_STR, CH_THR - }; - BlockPIDDfb pidStr; - BlockPID pidThr; public: - ControllerCar(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal), - _group(k_cntrl, PSTR("CNTRL_")), - _mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")), - pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, - steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut), - pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP, - throttleI, throttleD, throttleIMax, throttleYMax, - throttleDFCut) { - _hal->debug->println_P(PSTR("initializing car controller")); + ControllerCar(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal,new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9), ch_mode), + pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, + steeringI, steeringD, steeringIMax, steeringYMax,steeringDFCut), + pidThrust(new AP_Var_group(k_pidThrust, PSTR("THR_")), 1, throttleP, + throttleI, throttleD, throttleIMax, throttleYMax, + throttleDFCut), _strCmd(0), _thrustCmd(0) + { + _hal->debug->println_P(PSTR("initializing car controller")); - _hal->rc.push_back( - new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 7, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1540, - 1900, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, - 1900, RC_MODE_INOUT, false)); - } - virtual MAV_MODE getMode() { - return (MAV_MODE) _mode.get(); - } - virtual void update(const float & dt) { + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 3, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThrust, PSTR("THR_"), APM_RC, 2, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + } - // check for heartbeat - if (_hal->heartBeatLost()) { - _mode = MAV_MODE_FAILSAFE; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n")); - return; - // if throttle less than 5% cut motor power - } else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) { - _mode = MAV_MODE_LOCKED; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_STANDBY); - return; - // if in live mode then set state to active - } else if (_hal->getMode() == MODE_LIVE) { - _hal->setState(MAV_STATE_ACTIVE); - // if in hardware in the loop (control) mode, set to hilsim - } else if (_hal->getMode() == MODE_HIL_CNTL) { - _hal->setState(MAV_STATE_HILSIM); - } - - // read switch to set mode - if (_hal->rc[CH_MODE]->getRadioPosition() > 0) { - _mode = MAV_MODE_MANUAL; - } else { - _mode = MAV_MODE_AUTO; - } +private: + // methods + void manualLoop(const float dt) { + setAllRadioChannelsManually(); + _strCmd = _hal->rc[ch_str]->getRadioPosition(); + _thrustCmd = _hal->rc[ch_thrust]->getRadioPosition(); + } + void autoLoop(const float dt) { + //_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_thrust]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition()); + _strCmd = pidStr.update(_guide->getHeadingError(), _nav->getYawRate(), dt); + _thrustCmd = pidThrust.update( + _guide->getGroundSpeedCommand() + - _nav->getGroundSpeed(), dt); + } + void setMotorsActive() { + // turn all motors off if below 0.1 throttle + if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) { + setAllRadioChannelsToNeutral(); + } else { + _hal->rc[ch_thrust]->setPosition(_thrustCmd); + _hal->rc[ch_str]->setPosition(_strCmd); + } + } - // manual mode - switch (_mode) { - - case MAV_MODE_MANUAL: { - setAllRadioChannelsManually(); - //_hal->debug->println("manual"); - break; - } - case MAV_MODE_AUTO: { - float headingError = _guide->getHeadingCommand() - - _nav->getYaw(); - if (headingError > 180 * deg2Rad) - headingError -= 360 * deg2Rad; - if (headingError < -180 * deg2Rad) - headingError += 360 * deg2Rad; - _hal->rc[CH_STR]->setPosition( - pidStr.update(headingError, _nav->getYawRate(), dt)); - _hal->rc[CH_THR]->setPosition( - pidThr.update( - _guide->getGroundSpeedCommand() - - _nav->getGroundSpeed(), dt)); - //_hal->debug->println("automode"); - break; - } - - default: { - setAllRadioChannelsToNeutral(); - _mode = MAV_MODE_FAILSAFE; - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("unknown controller mode\n")); - break; - } - - } - } + // attributes + enum { + ch_mode = 0, ch_str, ch_thrust + }; + enum { + k_chMode = k_radioChannelsStart, k_chStr, k_chThrust + }; + enum { + k_pidStr = k_controllersStart, k_pidThrust + }; + BlockPIDDfb pidStr; + BlockPID pidThrust; + float _strCmd, _thrustCmd; }; } // namespace apo #endif /* CONTROLLERCAR_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/ArduRover/ControllerTank.h b/ArduRover/ControllerTank.h index 2e0958569c..0c091d6d70 100644 --- a/ArduRover/ControllerTank.h +++ b/ArduRover/ControllerTank.h @@ -13,121 +13,79 @@ namespace apo { class ControllerTank: public AP_Controller { -private: - AP_Var_group _group; - AP_Uint8 _mode; - enum { - k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr - }; - enum { - k_pidStr = k_controllersStart, k_pidThr - }; - enum { - CH_MODE = 0, CH_LEFT, CH_RIGHT, CH_STR, CH_THR - }; - BlockPIDDfb pidStr; - BlockPID pidThr; public: - ControllerTank(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal), - _group(k_cntrl, PSTR("CNTRL_")), - _mode(&_group, 1, MAV_MODE_UNINIT, PSTR("MODE")), - pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, - steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut), - pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP, - throttleI, throttleD, throttleIMax, throttleYMax, - throttleDFCut) { - _hal->debug->println_P(PSTR("initializing tank controller")); + ControllerTank(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_str,0.1,-0.9,0.9),ch_mode), + pidStr(new AP_Var_group(k_pidStr, PSTR("STR_")), 1, steeringP, + steeringI, steeringD, steeringIMax, steeringYMax, steeringDFCut), + pidThr(new AP_Var_group(k_pidThr, PSTR("THR_")), 1, throttleP, + throttleI, throttleD, throttleIMax, throttleYMax, + throttleDFCut), _headingOutput(0), _throttleOutput(0) { + _hal->debug->println_P(PSTR("initializing tank controller")); - _hal->rc.push_back( - new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500, - 1900, RC_MODE_OUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500, - 1900, RC_MODE_OUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500, - 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, - 1900, RC_MODE_IN, false)); - } - virtual MAV_MODE getMode() { - return (MAV_MODE) _mode.get(); - } - void mix(float headingOutput, float throttleOutput) { - _hal->rc[CH_LEFT]->setPosition(throttleOutput + headingOutput); - _hal->rc[CH_RIGHT]->setPosition(throttleOutput - headingOutput); - } - virtual void update(const float & dt) { + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 0, 1100, 1500, + 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chStr, PSTR("STR_"), APM_RC, 0, 1100, 1500, + 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THR_"), APM_RC, 1, 1100, 1500, + 1900, RC_MODE_IN, false)); + } - // check for heartbeat - if (_hal->heartBeatLost()) { - _mode = MAV_MODE_FAILSAFE; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n")); - return; - // if throttle less than 5% cut motor power - } else if (_hal->rc[CH_THR]->getRadioPosition() < 0.05) { - _mode = MAV_MODE_LOCKED; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_STANDBY); - return; - // if in live mode then set state to active - } else if (_hal->getMode() == MODE_LIVE) { - _hal->setState(MAV_STATE_ACTIVE); - // if in hardware in the loop (control) mode, set to hilsim - } else if (_hal->getMode() == MODE_HIL_CNTL) { - _hal->setState(MAV_STATE_HILSIM); - } - - // read switch to set mode - if (_hal->rc[CH_MODE]->getRadioPosition() > 0) { - _mode = MAV_MODE_MANUAL; - } else { - _mode = MAV_MODE_AUTO; - } +private: + // methods + void manualLoop(const float dt) { + setAllRadioChannelsManually(); + _headingOutput = _hal->rc[ch_str]->getPosition(); + _throttleOutput = _hal->rc[ch_thrust]->getPosition(); + } + void autoLoop(const float dt) { + float headingError = _guide->getHeadingCommand() + - _nav->getYaw(); + if (headingError > 180 * deg2Rad) + headingError -= 360 * deg2Rad; + if (headingError < -180 * deg2Rad) + headingError += 360 * deg2Rad; + _headingOutput = pidStr.update(headingError, _nav->getYawRate(), dt); + _throttleOutput = pidThr.update(_guide->getGroundSpeedCommand() + - _nav->getGroundSpeed(), dt); + } + void setMotorsActive() { + // turn all motors off if below 0.1 throttle + if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) { + setAllRadioChannelsToNeutral(); + } else { + _hal->rc[ch_left]->setPosition(_throttleOutput + _headingOutput); + _hal->rc[ch_right]->setPosition(_throttleOutput - _headingOutput); + } + } - // manual mode - switch (_mode) { - - case MAV_MODE_MANUAL: { - setAllRadioChannelsManually(); - mix(_hal->rc[CH_STR]->getPosition(), - _hal->rc[CH_THR]->getPosition()); - break; - } - case MAV_MODE_AUTO: { - float headingError = _guide->getHeadingCommand() - - _nav->getYaw(); - if (headingError > 180 * deg2Rad) - headingError -= 360 * deg2Rad; - if (headingError < -180 * deg2Rad) - headingError += 360 * deg2Rad; - mix(pidStr.update(headingError, _nav->getYawRate(), dt), - pidThr.update(_guide->getGroundSpeedCommand() - - _nav->getGroundSpeed(), dt)); - //_hal->debug->println("automode"); - break; - } - - default: { - setAllRadioChannelsToNeutral(); - _mode = MAV_MODE_FAILSAFE; - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("unknown controller mode\n")); - break; - } - - } - } + // attributes + enum { + k_chMode = k_radioChannelsStart, k_chLeft, k_chRight, k_chStr, k_chThr + }; + enum { + k_pidStr = k_controllersStart, k_pidThr + }; + enum { + ch_mode = 0, ch_left, ch_right, ch_str, ch_thrust + }; + BlockPIDDfb pidStr; + BlockPID pidThr; + float _headingOutput; + float _throttleOutput; }; } // namespace apo #endif /* CONTROLLERTANK_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/ArduRover/TankGeneric.h b/ArduRover/TankGeneric.h index 10e5af72a3..106eeca20a 100644 --- a/ArduRover/TankGeneric.h +++ b/ArduRover/TankGeneric.h @@ -5,6 +5,8 @@ * Author: jgoppert */ +// NOT CURRENTLY WORKING + #ifndef TANKGENERIC_H_ #define TANKGENERIC_H_ @@ -27,10 +29,10 @@ static const uint8_t heartBeatTimeout = 3; #define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL // baud rates -static uint32_t debugBaud = 57600; -static uint32_t telemBaud = 57600; -static uint32_t gpsBaud = 38400; -static uint32_t hilBaud = 57600; +static const uint32_t debugBaud = 57600; +static const uint32_t telemBaud = 57600; +static const uint32_t gpsBaud = 38400; +static const uint32_t hilBaud = 57600; // optional sensors static const bool gpsEnabled = false; @@ -75,6 +77,12 @@ const float throttleIMax = 0.0; const float throttleYMax = 0.0; const float throttleDFCut = 3.0; +// guidance +static const float velCmd = 5; +static const float xt = 10; +static const float xtLim = 90; + #include "ControllerTank.h" #endif /* TANKGENERIC_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 4db94cd354..c685556074 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -183,6 +183,12 @@ + + Form + + + Camera.cs + @@ -350,6 +356,9 @@ AGauge.cs Designer + + Camera.cs + Configuration.cs diff --git a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs new file mode 100644 index 0000000000..4382be0831 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs @@ -0,0 +1,421 @@ +namespace ArdupilotMega +{ + partial class Camera + { + /// + /// Required designer variable. + /// + private System.ComponentModel.IContainer components = null; + + /// + /// Clean up any resources being used. + /// + /// true if managed resources should be disposed; otherwise, false. + protected override void Dispose(bool disposing) + { + if (disposing && (components != null)) + { + components.Dispose(); + } + base.Dispose(disposing); + } + + #region Windows Form Designer generated code + + /// + /// Required method for Designer support - do not modify + /// the contents of this method with the code editor. + /// + private void InitializeComponent() + { + this.num_agl = new System.Windows.Forms.NumericUpDown(); + this.num_megapixel = new System.Windows.Forms.NumericUpDown(); + this.label2 = new System.Windows.Forms.Label(); + this.label3 = new System.Windows.Forms.Label(); + this.num_focallength = new System.Windows.Forms.NumericUpDown(); + this.label4 = new System.Windows.Forms.Label(); + this.num_focalmultip = new System.Windows.Forms.NumericUpDown(); + this.TXT_fovH = new System.Windows.Forms.TextBox(); + this.TXT_fovV = new System.Windows.Forms.TextBox(); + this.TXT_fovD = new System.Windows.Forms.TextBox(); + this.TXT_fovAD = new System.Windows.Forms.TextBox(); + this.TXT_fovAV = new System.Windows.Forms.TextBox(); + this.TXT_fovAH = new System.Windows.Forms.TextBox(); + this.TXT_cmpixel = new System.Windows.Forms.TextBox(); + this.TXT_imgwidth = new System.Windows.Forms.TextBox(); + this.TXT_imgheight = new System.Windows.Forms.TextBox(); + this.label1 = new System.Windows.Forms.Label(); + this.label5 = new System.Windows.Forms.Label(); + this.label6 = new System.Windows.Forms.Label(); + this.label7 = new System.Windows.Forms.Label(); + this.label8 = new System.Windows.Forms.Label(); + this.label9 = new System.Windows.Forms.Label(); + this.label10 = new System.Windows.Forms.Label(); + this.label11 = new System.Windows.Forms.Label(); + this.label12 = new System.Windows.Forms.Label(); + this.label13 = new System.Windows.Forms.Label(); + this.label14 = new System.Windows.Forms.Label(); + ((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_megapixel)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focalmultip)).BeginInit(); + this.SuspendLayout(); + // + // num_agl + // + this.num_agl.Location = new System.Drawing.Point(12, 12); + this.num_agl.Maximum = new decimal(new int[] { + 10000, + 0, + 0, + 0}); + this.num_agl.Name = "num_agl"; + this.num_agl.Size = new System.Drawing.Size(120, 20); + this.num_agl.TabIndex = 1; + this.num_agl.Value = new decimal(new int[] { + 200, + 0, + 0, + 0}); + this.num_agl.ValueChanged += new System.EventHandler(this.num_agl_ValueChanged); + // + // num_megapixel + // + this.num_megapixel.DecimalPlaces = 1; + this.num_megapixel.Increment = new decimal(new int[] { + 5, + 0, + 0, + 65536}); + this.num_megapixel.Location = new System.Drawing.Point(13, 38); + this.num_megapixel.Name = "num_megapixel"; + this.num_megapixel.Size = new System.Drawing.Size(120, 20); + this.num_megapixel.TabIndex = 2; + this.num_megapixel.Value = new decimal(new int[] { + 8, + 0, + 0, + 0}); + this.num_megapixel.ValueChanged += new System.EventHandler(this.num_megapixel_ValueChanged); + // + // label2 + // + this.label2.AutoSize = true; + this.label2.Location = new System.Drawing.Point(140, 19); + this.label2.Name = "label2"; + this.label2.Size = new System.Drawing.Size(72, 13); + this.label2.TabIndex = 4; + this.label2.Text = "Height m (agl)"; + // + // label3 + // + this.label3.AutoSize = true; + this.label3.Location = new System.Drawing.Point(140, 45); + this.label3.Name = "label3"; + this.label3.Size = new System.Drawing.Size(95, 13); + this.label3.TabIndex = 5; + this.label3.Text = "MegaPixel Camera"; + // + // num_focallength + // + this.num_focallength.DecimalPlaces = 1; + this.num_focallength.Increment = new decimal(new int[] { + 5, + 0, + 0, + 65536}); + this.num_focallength.Location = new System.Drawing.Point(245, 12); + this.num_focallength.Maximum = new decimal(new int[] { + 180, + 0, + 0, + 0}); + this.num_focallength.Minimum = new decimal(new int[] { + 1, + 0, + 0, + 0}); + this.num_focallength.Name = "num_focallength"; + this.num_focallength.Size = new System.Drawing.Size(120, 20); + this.num_focallength.TabIndex = 6; + this.num_focallength.Value = new decimal(new int[] { + 35, + 0, + 0, + 0}); + this.num_focallength.ValueChanged += new System.EventHandler(this.num_focallength_ValueChanged); + // + // label4 + // + this.label4.AutoSize = true; + this.label4.Location = new System.Drawing.Point(242, 72); + this.label4.Name = "label4"; + this.label4.Size = new System.Drawing.Size(99, 13); + this.label4.TabIndex = 8; + this.label4.Text = "2 x tan-1( l / (2 x f) )"; + // + // num_focalmultip + // + this.num_focalmultip.DecimalPlaces = 1; + this.num_focalmultip.Increment = new decimal(new int[] { + 1, + 0, + 0, + 65536}); + this.num_focalmultip.Location = new System.Drawing.Point(245, 38); + this.num_focalmultip.Maximum = new decimal(new int[] { + 5, + 0, + 0, + 0}); + this.num_focalmultip.Minimum = new decimal(new int[] { + 1, + 0, + 0, + 65536}); + this.num_focalmultip.Name = "num_focalmultip"; + this.num_focalmultip.Size = new System.Drawing.Size(120, 20); + this.num_focalmultip.TabIndex = 9; + this.num_focalmultip.Value = new decimal(new int[] { + 15, + 0, + 0, + 65536}); + this.num_focalmultip.ValueChanged += new System.EventHandler(this.num_focalmultip_ValueChanged); + // + // TXT_fovH + // + this.TXT_fovH.Location = new System.Drawing.Point(72, 138); + this.TXT_fovH.Name = "TXT_fovH"; + this.TXT_fovH.Size = new System.Drawing.Size(100, 20); + this.TXT_fovH.TabIndex = 10; + // + // TXT_fovV + // + this.TXT_fovV.Location = new System.Drawing.Point(72, 165); + this.TXT_fovV.Name = "TXT_fovV"; + this.TXT_fovV.Size = new System.Drawing.Size(100, 20); + this.TXT_fovV.TabIndex = 11; + // + // TXT_fovD + // + this.TXT_fovD.Location = new System.Drawing.Point(72, 192); + this.TXT_fovD.Name = "TXT_fovD"; + this.TXT_fovD.Size = new System.Drawing.Size(100, 20); + this.TXT_fovD.TabIndex = 12; + // + // TXT_fovAD + // + this.TXT_fovAD.Location = new System.Drawing.Point(286, 192); + this.TXT_fovAD.Name = "TXT_fovAD"; + this.TXT_fovAD.Size = new System.Drawing.Size(100, 20); + this.TXT_fovAD.TabIndex = 15; + // + // TXT_fovAV + // + this.TXT_fovAV.Location = new System.Drawing.Point(286, 165); + this.TXT_fovAV.Name = "TXT_fovAV"; + this.TXT_fovAV.Size = new System.Drawing.Size(100, 20); + this.TXT_fovAV.TabIndex = 14; + // + // TXT_fovAH + // + this.TXT_fovAH.Location = new System.Drawing.Point(286, 138); + this.TXT_fovAH.Name = "TXT_fovAH"; + this.TXT_fovAH.Size = new System.Drawing.Size(100, 20); + this.TXT_fovAH.TabIndex = 13; + // + // TXT_cmpixel + // + this.TXT_cmpixel.Location = new System.Drawing.Point(176, 218); + this.TXT_cmpixel.Name = "TXT_cmpixel"; + this.TXT_cmpixel.Size = new System.Drawing.Size(100, 20); + this.TXT_cmpixel.TabIndex = 16; + // + // TXT_imgwidth + // + this.TXT_imgwidth.Location = new System.Drawing.Point(93, 244); + this.TXT_imgwidth.Name = "TXT_imgwidth"; + this.TXT_imgwidth.Size = new System.Drawing.Size(100, 20); + this.TXT_imgwidth.TabIndex = 17; + // + // TXT_imgheight + // + this.TXT_imgheight.Location = new System.Drawing.Point(255, 244); + this.TXT_imgheight.Name = "TXT_imgheight"; + this.TXT_imgheight.Size = new System.Drawing.Size(100, 20); + this.TXT_imgheight.TabIndex = 18; + // + // label1 + // + this.label1.AutoSize = true; + this.label1.Location = new System.Drawing.Point(371, 19); + this.label1.Name = "label1"; + this.label1.Size = new System.Drawing.Size(69, 13); + this.label1.TabIndex = 19; + this.label1.Text = "Focal Length"; + // + // label5 + // + this.label5.AutoSize = true; + this.label5.Location = new System.Drawing.Point(371, 45); + this.label5.Name = "label5"; + this.label5.Size = new System.Drawing.Size(88, 13); + this.label5.TabIndex = 20; + this.label5.Text = "Frame Muli factor"; + // + // label6 + // + this.label6.AutoSize = true; + this.label6.Location = new System.Drawing.Point(9, 145); + this.label6.Name = "label6"; + this.label6.Size = new System.Drawing.Size(36, 13); + this.label6.TabIndex = 21; + this.label6.Text = "Dist H"; + // + // label7 + // + this.label7.AutoSize = true; + this.label7.Location = new System.Drawing.Point(235, 145); + this.label7.Name = "label7"; + this.label7.Size = new System.Drawing.Size(45, 13); + this.label7.TabIndex = 22; + this.label7.Text = "Angle H"; + // + // label8 + // + this.label8.AutoSize = true; + this.label8.Location = new System.Drawing.Point(236, 172); + this.label8.Name = "label8"; + this.label8.Size = new System.Drawing.Size(44, 13); + this.label8.TabIndex = 23; + this.label8.Text = "Angle V"; + // + // label9 + // + this.label9.AutoSize = true; + this.label9.Location = new System.Drawing.Point(235, 199); + this.label9.Name = "label9"; + this.label9.Size = new System.Drawing.Size(45, 13); + this.label9.TabIndex = 24; + this.label9.Text = "Angle D"; + // + // label10 + // + this.label10.AutoSize = true; + this.label10.Location = new System.Drawing.Point(10, 172); + this.label10.Name = "label10"; + this.label10.Size = new System.Drawing.Size(35, 13); + this.label10.TabIndex = 25; + this.label10.Text = "Dist V"; + // + // label11 + // + this.label11.AutoSize = true; + this.label11.Location = new System.Drawing.Point(10, 199); + this.label11.Name = "label11"; + this.label11.Size = new System.Drawing.Size(36, 13); + this.label11.TabIndex = 26; + this.label11.Text = "Dist D"; + // + // label12 + // + this.label12.AutoSize = true; + this.label12.Location = new System.Drawing.Point(125, 225); + this.label12.Name = "label12"; + this.label12.Size = new System.Drawing.Size(50, 13); + this.label12.TabIndex = 27; + this.label12.Text = "CM/Pixel"; + // + // label13 + // + this.label13.AutoSize = true; + this.label13.Location = new System.Drawing.Point(37, 251); + this.label13.Name = "label13"; + this.label13.Size = new System.Drawing.Size(39, 13); + this.label13.TabIndex = 28; + this.label13.Text = "Pixel X"; + // + // label14 + // + this.label14.AutoSize = true; + this.label14.Location = new System.Drawing.Point(199, 253); + this.label14.Name = "label14"; + this.label14.Size = new System.Drawing.Size(39, 13); + this.label14.TabIndex = 29; + this.label14.Text = "Pixel Y"; + // + // Camera + // + this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F); + this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.ClientSize = new System.Drawing.Size(473, 275); + this.Controls.Add(this.label14); + this.Controls.Add(this.label13); + this.Controls.Add(this.label12); + this.Controls.Add(this.label11); + this.Controls.Add(this.label10); + this.Controls.Add(this.label9); + this.Controls.Add(this.label8); + this.Controls.Add(this.label7); + this.Controls.Add(this.label6); + this.Controls.Add(this.label5); + this.Controls.Add(this.label1); + this.Controls.Add(this.TXT_imgheight); + this.Controls.Add(this.TXT_imgwidth); + this.Controls.Add(this.TXT_cmpixel); + this.Controls.Add(this.TXT_fovAD); + this.Controls.Add(this.TXT_fovAV); + this.Controls.Add(this.TXT_fovAH); + this.Controls.Add(this.TXT_fovD); + this.Controls.Add(this.TXT_fovV); + this.Controls.Add(this.TXT_fovH); + this.Controls.Add(this.num_focalmultip); + this.Controls.Add(this.label4); + this.Controls.Add(this.num_focallength); + this.Controls.Add(this.label3); + this.Controls.Add(this.label2); + this.Controls.Add(this.num_megapixel); + this.Controls.Add(this.num_agl); + this.Name = "Camera"; + this.Text = "Camera"; + ((System.ComponentModel.ISupportInitialize)(this.num_agl)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_megapixel)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focallength)).EndInit(); + ((System.ComponentModel.ISupportInitialize)(this.num_focalmultip)).EndInit(); + this.ResumeLayout(false); + this.PerformLayout(); + + } + + #endregion + + private System.Windows.Forms.NumericUpDown num_agl; + private System.Windows.Forms.NumericUpDown num_megapixel; + private System.Windows.Forms.Label label2; + private System.Windows.Forms.Label label3; + private System.Windows.Forms.NumericUpDown num_focallength; + private System.Windows.Forms.Label label4; + private System.Windows.Forms.NumericUpDown num_focalmultip; + private System.Windows.Forms.TextBox TXT_fovH; + private System.Windows.Forms.TextBox TXT_fovV; + private System.Windows.Forms.TextBox TXT_fovD; + private System.Windows.Forms.TextBox TXT_fovAD; + private System.Windows.Forms.TextBox TXT_fovAV; + private System.Windows.Forms.TextBox TXT_fovAH; + private System.Windows.Forms.TextBox TXT_cmpixel; + private System.Windows.Forms.TextBox TXT_imgwidth; + private System.Windows.Forms.TextBox TXT_imgheight; + private System.Windows.Forms.Label label1; + private System.Windows.Forms.Label label5; + private System.Windows.Forms.Label label6; + private System.Windows.Forms.Label label7; + private System.Windows.Forms.Label label8; + private System.Windows.Forms.Label label9; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.Label label13; + private System.Windows.Forms.Label label14; + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Camera.cs b/Tools/ArdupilotMegaPlanner/Camera.cs new file mode 100644 index 0000000000..afbb9d1fa0 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Camera.cs @@ -0,0 +1,139 @@ +using System; +using System.Collections.Generic; +using System.ComponentModel; +using System.Data; +using System.Drawing; +using System.Linq; +using System.Text; +using System.Windows.Forms; + +namespace ArdupilotMega +{ + public partial class Camera : Form + { + float mm_2_feet = 1 / 304.8f; + float feet_2_mm = 304.8f; + const float rad2deg = (float)(180 / Math.PI); + const float deg2rad = (float)(1.0 / rad2deg); + + public Camera() + { + InitializeComponent(); + } + + private void numericUpDown1_ValueChanged(object sender, EventArgs e) + { + doCalc(); + } + + void doCalc() + { + + var film_width = 36.0f; + var film_height = 27.0f; + var film_diag = 0.0f; + + var flen = (float)num_focallength.Value; + var flen_mult = (float)num_focalmultip.Value; + var subj_dist = (float)num_agl.Value; + + //if (isNaN(flen_mult) || flen_mult<=0) + { + //f.flen_mult = 1; + //flen_mult = 1; + } + + // convert distance to mm + /* + if (f.units.value.search(/feet/i) != -1) + { + //user input in feet + subj_dist = subj_dist * feet_2_mm; + } + else */ + { + //user input in m + subj_dist = subj_dist * 1000; + } + + //Account for focal length multiplier (actually, a film/sensor size multiplier) + film_width = film_width / flen_mult; + film_height = film_height / flen_mult; + film_diag = (int)(Math.Sqrt((film_width * film_width) + (film_height * film_height))); + + var half_fov_h = (Math.Atan(film_width / (2 * flen))); + var fov_h = 2 * (subj_dist * Math.Tan(half_fov_h)); + + var half_fov_v = (Math.Atan(film_height / (2 * flen))); + var fov_v = 2 * (subj_dist * Math.Tan(half_fov_v)); + + var half_fov_d = (Math.Atan(film_diag / (2 * flen))); + var fov_d = 2 * (subj_dist * Math.Tan(half_fov_d)); + + //convert answer (currently in mm) back to feet + fov_h = fov_h * mm_2_feet; + fov_v = fov_v * mm_2_feet; + fov_d = fov_d * mm_2_feet; + /* + if (f.units.value.search(/feet/i) != -1) + { + f.fov_h.value = feet_inches(fov_h); + f.fov_v.value = feet_inches(fov_v); + f.fov_d.value = feet_inches(fov_d); + } + else */ + { + TXT_fovH.Text = meters(fov_h); + TXT_fovV.Text = meters(fov_v); + TXT_fovD.Text = meters(fov_d); + + TXT_fovAH.Text = (half_fov_h * 2 * rad2deg).ToString("0.00"); + TXT_fovAV.Text = (half_fov_v * 2 * rad2deg).ToString("0.00"); + TXT_fovAD.Text = (half_fov_d * 2 * rad2deg).ToString("0.00"); + + float test1 = (float)Math.Sqrt((float)num_megapixel.Value * 1000000 * (film_height / film_width)); + + TXT_imgwidth.Text = test1.ToString("0"); + TXT_imgheight.Text = (((float)num_megapixel.Value * 1000000) / test1).ToString("0"); + + + TXT_cmpixel.Text = (((fov_h * feet_2_mm) / 10.0) / test1).ToString("0.000 cm"); + } + } + + + //Takes a distance in feet and converts to string representation in meters/cm + string meters(double aNumber) + { + //if (isNaN(aNumber)) + //return aNumber; + + var mm = aNumber * feet_2_mm; + + var m = Math.Floor(mm / 1000); + var cm = (mm / 10) % 100; + + return m + "m " + cm.ToString("0.00") + "cm"; + } + + private void num_agl_ValueChanged(object sender, EventArgs e) + { + doCalc(); + } + + private void num_megapixel_ValueChanged(object sender, EventArgs e) + { + doCalc(); + } + + private void num_focallength_ValueChanged(object sender, EventArgs e) + { + doCalc(); + } + + private void num_focalmultip_ValueChanged(object sender, EventArgs e) + { + doCalc(); + } + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Camera.resx b/Tools/ArdupilotMegaPlanner/Camera.resx new file mode 100644 index 0000000000..7080a7d118 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/Camera.resx @@ -0,0 +1,120 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + text/microsoft-resx + + + 2.0 + + + System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 8febc24fd3..9a5b0f3166 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -147,6 +147,10 @@ namespace ArdupilotMega public ushort rcoverridech2 { get; set; } public ushort rcoverridech3 { get; set; } public ushort rcoverridech4 { get; set; } + public ushort rcoverridech5 { get; set; } + public ushort rcoverridech6 { get; set; } + public ushort rcoverridech7 { get; set; } + public ushort rcoverridech8 { get; set; } // current firmware public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane; @@ -187,10 +191,15 @@ namespace ArdupilotMega public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs) { - UpdateCurrentSettings(bs, false); + UpdateCurrentSettings(bs, false, MainV2.comPort); } public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow) + { + UpdateCurrentSettings(bs, false, MainV2.comPort); + } + + public void UpdateCurrentSettings(System.Windows.Forms.BindingSource bs, bool updatenow, MAVLink mavinterface) { if (DateTime.Now > lastupdate.AddMilliseconds(19) || updatenow) // 50 hz { @@ -203,10 +212,10 @@ namespace ArdupilotMega } // Console.WriteLine("Updating CurrentState " + DateTime.Now.Millisecond); - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text { - string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6); + string logdata = DateTime.Now + " " + Encoding.ASCII.GetString(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT], 6, mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT].Length - 6); int ind = logdata.IndexOf('\0'); if (ind != -1) @@ -217,16 +226,16 @@ namespace ArdupilotMega } messages.Add(logdata + "\n"); - MAVLink.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null; + mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] != null) // hil + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] != null) // hil { var hil = new ArdupilotMega.MAVLink.__mavlink_rc_channels_scaled_t(); object temp = hil; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED], ref temp, 6); hil = (MAVLink.__mavlink_rc_channels_scaled_t)(temp); @@ -242,13 +251,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_SCALED] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] != null) { MAVLink.__mavlink_nav_controller_output_t nav = new MAVLink.__mavlink_nav_controller_output_t(); object temp = nav; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT], ref temp, 6); nav = (MAVLink.__mavlink_nav_controller_output_t)(temp); @@ -264,13 +273,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT] = null; } - if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] != null) + if (mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] != null) { ArdupilotMega.MAVLink.__mavlink_sys_status_t sysstatus = new ArdupilotMega.MAVLink.__mavlink_sys_status_t(); object temp = sysstatus; - MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS], ref temp, 6); sysstatus = (ArdupilotMega.MAVLink.__mavlink_sys_status_t)(temp); @@ -377,13 +386,13 @@ namespace ArdupilotMega //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null) { var att = new ArdupilotMega.MAVLink.__mavlink_attitude_t(); object temp = att; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE], ref temp, 6); att = (MAVLink.__mavlink_attitude_t)(temp); @@ -396,13 +405,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] != null) { var gps = new MAVLink.__mavlink_gps_raw_t(); object temp = gps; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW], ref temp, 6); gps = (MAVLink.__mavlink_gps_raw_t)(temp); @@ -421,26 +430,26 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS] != null) { var gps = new MAVLink.__mavlink_gps_status_t(); object temp = gps; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS], ref temp, 6); gps = (MAVLink.__mavlink_gps_status_t)(temp); satcount = gps.satellites_visible; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT] != null) { var loc = new MAVLink.__mavlink_global_position_int_t(); object temp = loc; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT], ref temp, 6); loc = (MAVLink.__mavlink_global_position_int_t)(temp); @@ -449,13 +458,13 @@ namespace ArdupilotMega lng = loc.lon / 10000000.0f; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION] != null) { var loc = new MAVLink.__mavlink_global_position_t(); object temp = loc; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION], ref temp, 6); loc = (MAVLink.__mavlink_global_position_t)(temp); @@ -464,13 +473,13 @@ namespace ArdupilotMega lng = loc.lon; } - if (MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] != null) + if (mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] != null) { ArdupilotMega.MAVLink.__mavlink_waypoint_current_t wpcur = new ArdupilotMega.MAVLink.__mavlink_waypoint_current_t(); object temp = wpcur; - MAVLink.ByteArrayToStructure(MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT], ref temp, 6); wpcur = (ArdupilotMega.MAVLink.__mavlink_waypoint_current_t)(temp); @@ -486,13 +495,13 @@ namespace ArdupilotMega //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] != null) { var rcin = new MAVLink.__mavlink_rc_channels_raw_t(); object temp = rcin; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW], ref temp, 6); rcin = (MAVLink.__mavlink_rc_channels_raw_t)(temp); @@ -508,13 +517,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] != null) { var servoout = new MAVLink.__mavlink_servo_output_raw_t(); object temp = servoout; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW], ref temp, 6); servoout = (MAVLink.__mavlink_servo_output_raw_t)(temp); @@ -530,13 +539,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] != null) { var imu = new MAVLink.__mavlink_raw_imu_t(); object temp = imu; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU], ref temp, 6); imu = (MAVLink.__mavlink_raw_imu_t)(temp); @@ -551,13 +560,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU] != null) { var imu = new MAVLink.__mavlink_scaled_imu_t(); object temp = imu; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU], ref temp, 6); imu = (MAVLink.__mavlink_scaled_imu_t)(temp); @@ -572,13 +581,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null) + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null) { MAVLink.__mavlink_vfr_hud_t vfr = new MAVLink.__mavlink_vfr_hud_t(); object temp = vfr; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD], ref temp, 6); vfr = (MAVLink.__mavlink_vfr_hud_t)(temp); @@ -602,13 +611,13 @@ namespace ArdupilotMega //MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] = null; } - if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO] != null) // hil + if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO] != null) // hil { var mem = new ArdupilotMega.MAVLink.__mavlink_meminfo_t(); object temp = mem; - MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO], ref temp, 6); + MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO], ref temp, 6); mem = (MAVLink.__mavlink_meminfo_t)(temp); diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log index 8c61efe92c..10604a699c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-1280.build.log @@ -46,7 +46,7 @@ autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' bu autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log index 8c61efe92c..10604a699c 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-HELHIL-2560.build.log @@ -46,7 +46,7 @@ autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' bu autogenerated:249: warning: 'long int read_barometer()' declared 'static' but never defined autogenerated:250: warning: 'void read_airspeed()' declared 'static' but never defined autogenerated:251: warning: 'void zero_airspeed()' declared 'static' but never defined -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log index 7131865864..d420f23d8f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.build.log @@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': /root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning /root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': -/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function -/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function autogenerated: At global scope: autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined @@ -34,7 +34,7 @@ autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' de autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt index 68bdfdcb08..41607607b2 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-1280.size.txt @@ -677,9 +677,9 @@ 000003a0 t read_battery() 0000045c T update_yaw_mode() 0000046e T update_roll_pitch_mode() -0000052e t heli_move_swash(int, int, int, int) +0000053e t heli_move_swash(int, int, int, int) 000005cc t __static_initialization_and_destruction_0(int, int) -00000640 t init_ardupilot() +00000620 t init_ardupilot() 0000071a t update_nav_wp() 000007ec t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log index 7131865864..d420f23d8f 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.build.log @@ -9,11 +9,11 @@ In file included from /root/apm/ardupilot-mega/ArduCopter/ArduCopter.pde:77: /root/apm/ardupilot-mega/ArduCopter/heli.pde: In function 'void heli_init_swash()': /root/apm/ardupilot-mega/ArduCopter/heli.pde:60: warning: comparisons like X<=Y<=Z do not have their mathematical meaning /root/apm/ardupilot-mega/ArduCopter/setup.pde: In function 'int8_t setup_heli(uint8_t, const Menu::arg*)': -/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function -/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_tail' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_tail' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_coll' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'min_coll' may be used uninitialized in this function +/root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_pitch' may be used uninitialized in this function /root/apm/ardupilot-mega/ArduCopter/setup.pde:467: warning: 'max_roll' may be used uninitialized in this function autogenerated: At global scope: autogenerated:109: warning: 'void Log_Write_Optflow()' declared 'static' but never defined @@ -34,7 +34,7 @@ autogenerated:238: warning: 'long int get_alt_distance(Location*, Location*)' de autogenerated:248: warning: 'long int read_baro_filtered()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/sensors.pde:95: warning: 'void read_airspeed()' defined but not used /root/apm/ardupilot-mega/ArduCopter/sensors.pde:100: warning: 'void zero_airspeed()' defined but not used -/root/apm/ardupilot-mega/ArduCopter/system.pde:434: warning: 'void set_failsafe(boolean)' defined but not used +/root/apm/ardupilot-mega/ArduCopter/system.pde:438: warning: 'void set_failsafe(boolean)' defined but not used autogenerated:285: warning: 'void init_optflow()' declared 'static' but never defined autogenerated:292: warning: 'void fake_out_gps()' declared 'static' but never defined /root/apm/ardupilot-mega/ArduCopter/test.pde:1028: warning: 'void print_motor_out()' defined but not used diff --git a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt index b936dfb003..0f00a831cc 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt +++ b/Tools/ArdupilotMegaPlanner/Firmware/AC2-Heli-2560.size.txt @@ -677,9 +677,9 @@ 000003a0 t read_battery() 0000045c T update_yaw_mode() 0000046e T update_roll_pitch_mode() -0000052e t heli_move_swash(int, int, int, int) +0000053e t heli_move_swash(int, int, int, int) 000005cc t __static_initialization_and_destruction_0(int, int) -0000063e t init_ardupilot() +0000061e t init_ardupilot() 0000071a t update_nav_wp() 000007e8 t setup_heli(unsigned char, Menu::arg const*) 00000870 t process_next_command() diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index d39b47fa9a..c2dccc3239 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -99,6 +99,7 @@ #define AUTO_RESET_LOITER 0 #define FRAME_CONFIG HELI_FRAME +#define INSTANT_PWM ENABLED // DEFAULT PIDS diff --git a/Tools/ArdupilotMegaPlanner/Firmware/git.log b/Tools/ArdupilotMegaPlanner/Firmware/git.log index 2a7bfed917..04b288c7e4 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/git.log +++ b/Tools/ArdupilotMegaPlanner/Firmware/git.log @@ -1 +1,36 @@ -Already up-to-date. +From https://code.google.com/p/ardupilot-mega + 8a21477..b0bfa54 APM_Camera -> origin/APM_Camera + 6f44fff..076459c master -> origin/master +Updating 6f44fff..076459c +Fast-forward + ArduCopter/control_modes.pde | 16 + + ArduCopter/defines.h | 1 + + ArduCopter/system.pde | 4 + + ArduPlane/ArduPlane.pde | 10 +- + ArduPlane/Parameters.h | 3 + + ArduPlane/config.h | 8 + + Tools/ArduTracker/tags |148411 -------------------- + Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs | 2 + + Tools/ArdupilotMegaPlanner/Log.cs | 174 +- + Tools/ArdupilotMegaPlanner/MainV2.cs | 9 +- + .../Properties/AssemblyInfo.cs | 2 +- + .../bin/Release/ArdupilotMegaPlanner.application | 2 +- + .../bin/Release/ArdupilotMegaPlanner.exe | Bin 2194432 -> 2194944 bytes + Tools/ArdupilotMegaPlanner/bin/Release/Updater.exe | Bin 8192 -> 8192 bytes + Tools/ArdupilotMegaPlanner/bin/Release/resedit.exe | Bin 20480 -> 20480 bytes + .../ru-RU/ArdupilotMegaPlanner.resources.dll | Bin 53248 -> 53248 bytes + .../zh-Hans/ArdupilotMegaPlanner.resources.dll | Bin 380928 -> 380928 bytes + apo/ControllerQuad.h | 51 +- + apo/QuadArducopter.h | 10 +- + libraries/APO/AP_ArmingMechanism.cpp | 57 + + libraries/APO/AP_ArmingMechanism.h | 67 + + libraries/APO/AP_BatteryMonitor.cpp | 2 + + libraries/APO/AP_BatteryMonitor.h | 58 +- + libraries/APO/AP_Guide.h | 1 + + libraries/APO/AP_HardwareAbstractionLayer.h | 13 + + libraries/APO/AP_Navigator.cpp | 20 +- + libraries/Desktop/support/FastSerial.cpp | 283 +- + 27 files changed, 517 insertions(+), 148687 deletions(-) + delete mode 100644 Tools/ArduTracker/tags + create mode 100644 libraries/APO/AP_ArmingMechanism.cpp + create mode 100644 libraries/APO/AP_ArmingMechanism.h diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs index 924463c992..79df55f2e2 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs @@ -289,8 +289,6 @@ namespace ArdupilotMega.GCSViews internal void processToScreen() { - - Params.Rows.Clear(); // process hashdefines and update display @@ -343,7 +341,7 @@ namespace ArdupilotMega.GCSViews { try { - toolTip1.SetToolTip(ctl, tooltips[value].ToString()); + toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc); } catch { } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index e7d970530f..067b30f823 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -563,7 +563,7 @@ namespace ArdupilotMega.GCSViews this.Refresh(); Console.WriteLine("Downloaded"); } - catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.Message); return; } + catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.ToString()); return; } UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 39e165613e..bddd7f9853 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -50,6 +50,11 @@ this.BUT_playlog = new ArdupilotMega.MyButton(); this.BUT_loadtelem = new ArdupilotMega.MyButton(); this.tableMap = new System.Windows.Forms.TableLayoutPanel(); + this.splitContainer1 = new System.Windows.Forms.SplitContainer(); + this.zg1 = new ZedGraph.ZedGraphControl(); + this.lbl_winddir = new ArdupilotMega.MyLabel(); + this.lbl_windvel = new ArdupilotMega.MyLabel(); + this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl(); this.panel1 = new System.Windows.Forms.Panel(); this.TXT_lat = new ArdupilotMega.MyLabel(); this.Zoomlevel = new System.Windows.Forms.NumericUpDown(); @@ -58,11 +63,6 @@ this.TXT_alt = new ArdupilotMega.MyLabel(); this.CHK_autopan = new System.Windows.Forms.CheckBox(); this.CB_tuning = new System.Windows.Forms.CheckBox(); - this.panel2 = new System.Windows.Forms.Panel(); - this.lbl_windvel = new ArdupilotMega.MyLabel(); - this.lbl_winddir = new ArdupilotMega.MyLabel(); - this.gMapControl1 = new GMap.NET.WindowsForms.GMapControl(); - this.zg1 = new ZedGraph.ZedGraphControl(); this.dataGridViewImageColumn1 = new System.Windows.Forms.DataGridViewImageColumn(); this.dataGridViewImageColumn2 = new System.Windows.Forms.DataGridViewImageColumn(); this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components); @@ -84,9 +84,11 @@ ((System.ComponentModel.ISupportInitialize)(this.NUM_playbackspeed)).BeginInit(); ((System.ComponentModel.ISupportInitialize)(this.tracklog)).BeginInit(); this.tableMap.SuspendLayout(); + this.splitContainer1.Panel1.SuspendLayout(); + this.splitContainer1.Panel2.SuspendLayout(); + this.splitContainer1.SuspendLayout(); this.panel1.SuspendLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).BeginInit(); - this.panel2.SuspendLayout(); this.SuspendLayout(); // // contextMenuStrip1 @@ -1042,10 +1044,80 @@ // tableMap // resources.ApplyResources(this.tableMap, "tableMap"); + this.tableMap.Controls.Add(this.splitContainer1, 0, 0); this.tableMap.Controls.Add(this.panel1, 0, 1); - this.tableMap.Controls.Add(this.panel2, 0, 0); this.tableMap.Name = "tableMap"; // + // splitContainer1 + // + resources.ApplyResources(this.splitContainer1, "splitContainer1"); + this.splitContainer1.Name = "splitContainer1"; + // + // splitContainer1.Panel1 + // + this.splitContainer1.Panel1.Controls.Add(this.zg1); + this.splitContainer1.Panel1Collapsed = true; + // + // splitContainer1.Panel2 + // + this.splitContainer1.Panel2.Controls.Add(this.lbl_winddir); + this.splitContainer1.Panel2.Controls.Add(this.lbl_windvel); + this.splitContainer1.Panel2.Controls.Add(this.gMapControl1); + // + // zg1 + // + resources.ApplyResources(this.zg1, "zg1"); + this.zg1.Name = "zg1"; + this.zg1.ScrollGrace = 0D; + this.zg1.ScrollMaxX = 0D; + this.zg1.ScrollMaxY = 0D; + this.zg1.ScrollMaxY2 = 0D; + this.zg1.ScrollMinX = 0D; + this.zg1.ScrollMinY = 0D; + this.zg1.ScrollMinY2 = 0D; + this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); + // + // lbl_winddir + // + this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); + resources.ApplyResources(this.lbl_winddir, "lbl_winddir"); + this.lbl_winddir.Name = "lbl_winddir"; + this.lbl_winddir.resize = true; + this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip")); + // + // lbl_windvel + // + this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0")); + resources.ApplyResources(this.lbl_windvel, "lbl_windvel"); + this.lbl_windvel.Name = "lbl_windvel"; + this.lbl_windvel.resize = true; + this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip")); + // + // gMapControl1 + // + this.gMapControl1.BackColor = System.Drawing.Color.Transparent; + this.gMapControl1.Bearing = 0F; + this.gMapControl1.CanDragMap = true; + this.gMapControl1.ContextMenuStrip = this.contextMenuStrip1; + resources.ApplyResources(this.gMapControl1, "gMapControl1"); + this.gMapControl1.GrayScaleMode = false; + this.gMapControl1.LevelsKeepInMemmory = 5; + this.gMapControl1.MarkersEnabled = true; + this.gMapControl1.MaxZoom = 2; + this.gMapControl1.MinZoom = 2; + this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter; + this.gMapControl1.Name = "gMapControl1"; + this.gMapControl1.NegativeMode = false; + this.gMapControl1.PolygonsEnabled = true; + this.gMapControl1.RetryLoadTile = 0; + this.gMapControl1.RoutesEnabled = true; + this.gMapControl1.ShowTileGridLines = false; + this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg"))); + this.gMapControl1.Zoom = 0D; + this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click); + this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); + this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); + // // panel1 // this.panel1.Controls.Add(this.TXT_lat); @@ -1130,69 +1202,6 @@ this.CB_tuning.UseVisualStyleBackColor = true; this.CB_tuning.CheckedChanged += new System.EventHandler(this.CB_tuning_CheckedChanged); // - // panel2 - // - this.panel2.Controls.Add(this.lbl_windvel); - this.panel2.Controls.Add(this.lbl_winddir); - this.panel2.Controls.Add(this.gMapControl1); - this.panel2.Controls.Add(this.zg1); - resources.ApplyResources(this.panel2, "panel2"); - this.panel2.Name = "panel2"; - // - // lbl_windvel - // - this.lbl_windvel.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_vel", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Vel: 0")); - resources.ApplyResources(this.lbl_windvel, "lbl_windvel"); - this.lbl_windvel.Name = "lbl_windvel"; - this.lbl_windvel.resize = true; - this.toolTip1.SetToolTip(this.lbl_windvel, resources.GetString("lbl_windvel.ToolTip")); - // - // lbl_winddir - // - this.lbl_winddir.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.bindingSource1, "wind_dir", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "Dir: 0")); - resources.ApplyResources(this.lbl_winddir, "lbl_winddir"); - this.lbl_winddir.Name = "lbl_winddir"; - this.lbl_winddir.resize = true; - this.toolTip1.SetToolTip(this.lbl_winddir, resources.GetString("lbl_winddir.ToolTip")); - // - // gMapControl1 - // - this.gMapControl1.BackColor = System.Drawing.Color.Transparent; - this.gMapControl1.Bearing = 0F; - this.gMapControl1.CanDragMap = true; - this.gMapControl1.ContextMenuStrip = this.contextMenuStrip1; - resources.ApplyResources(this.gMapControl1, "gMapControl1"); - this.gMapControl1.GrayScaleMode = false; - this.gMapControl1.LevelsKeepInMemmory = 5; - this.gMapControl1.MarkersEnabled = true; - this.gMapControl1.MaxZoom = 2; - this.gMapControl1.MinZoom = 2; - this.gMapControl1.MouseWheelZoomType = GMap.NET.MouseWheelZoomType.MousePositionAndCenter; - this.gMapControl1.Name = "gMapControl1"; - this.gMapControl1.NegativeMode = false; - this.gMapControl1.PolygonsEnabled = true; - this.gMapControl1.RetryLoadTile = 0; - this.gMapControl1.RoutesEnabled = true; - this.gMapControl1.ShowTileGridLines = false; - this.gMapControl1.streamjpg = ((System.IO.MemoryStream)(resources.GetObject("gMapControl1.streamjpg"))); - this.gMapControl1.Zoom = 0D; - this.gMapControl1.Click += new System.EventHandler(this.gMapControl1_Click); - this.gMapControl1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseDown); - this.gMapControl1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.gMapControl1_MouseMove); - // - // zg1 - // - resources.ApplyResources(this.zg1, "zg1"); - this.zg1.Name = "zg1"; - this.zg1.ScrollGrace = 0D; - this.zg1.ScrollMaxX = 0D; - this.zg1.ScrollMaxY = 0D; - this.zg1.ScrollMaxY2 = 0D; - this.zg1.ScrollMinX = 0D; - this.zg1.ScrollMinY = 0D; - this.zg1.ScrollMinY2 = 0D; - this.zg1.DoubleClick += new System.EventHandler(this.zg1_DoubleClick); - // // dataGridViewImageColumn1 // dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter; @@ -1254,10 +1263,12 @@ ((System.ComponentModel.ISupportInitialize)(this.NUM_playbackspeed)).EndInit(); ((System.ComponentModel.ISupportInitialize)(this.tracklog)).EndInit(); this.tableMap.ResumeLayout(false); + this.splitContainer1.Panel1.ResumeLayout(false); + this.splitContainer1.Panel2.ResumeLayout(false); + this.splitContainer1.ResumeLayout(false); this.panel1.ResumeLayout(false); this.panel1.PerformLayout(); ((System.ComponentModel.ISupportInitialize)(this.Zoomlevel)).EndInit(); - this.panel2.ResumeLayout(false); this.ResumeLayout(false); } @@ -1294,7 +1305,6 @@ private ArdupilotMega.MyLabel TXT_long; private ArdupilotMega.MyLabel TXT_alt; private System.Windows.Forms.CheckBox CHK_autopan; - private System.Windows.Forms.Panel panel2; private GMap.NET.WindowsForms.GMapControl gMapControl1; private ZedGraph.ZedGraphControl zg1; private System.Windows.Forms.TabControl tabControl1; @@ -1320,5 +1330,6 @@ private System.Windows.Forms.ToolStripMenuItem stopRecordToolStripMenuItem; private MyLabel lbl_logpercent; private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem; + private System.Windows.Forms.SplitContainer splitContainer1; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 705de52256..af2806bda9 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -31,18 +31,33 @@ namespace ArdupilotMega.GCSViews RollingPointPairList list3 = new RollingPointPairList(1200); RollingPointPairList list4 = new RollingPointPairList(1200); RollingPointPairList list5 = new RollingPointPairList(1200); + RollingPointPairList list6 = new RollingPointPairList(1200); + RollingPointPairList list7 = new RollingPointPairList(1200); + RollingPointPairList list8 = new RollingPointPairList(1200); + RollingPointPairList list9 = new RollingPointPairList(1200); + RollingPointPairList list10 = new RollingPointPairList(1200); System.Reflection.PropertyInfo list1item = null; System.Reflection.PropertyInfo list2item = null; System.Reflection.PropertyInfo list3item = null; System.Reflection.PropertyInfo list4item = null; System.Reflection.PropertyInfo list5item = null; + System.Reflection.PropertyInfo list6item = null; + System.Reflection.PropertyInfo list7item = null; + System.Reflection.PropertyInfo list8item = null; + System.Reflection.PropertyInfo list9item = null; + System.Reflection.PropertyInfo list10item = null; CurveItem list1curve; CurveItem list2curve; CurveItem list3curve; CurveItem list4curve; CurveItem list5curve; + CurveItem list6curve; + CurveItem list7curve; + CurveItem list8curve; + CurveItem list9curve; + CurveItem list10curve; bool huddropout = false; bool huddropoutresize = false; @@ -77,10 +92,22 @@ namespace ArdupilotMega.GCSViews Control.CheckForIllegalCrossThreadCalls = false; // so can update display from another thread // setup default tuning graph - chk_box_CheckedChanged((object)(new CheckBox() { Name = "roll", Checked = true }), new EventArgs()); - chk_box_CheckedChanged((object)(new CheckBox() { Name = "pitch", Checked = true }), new EventArgs()); - chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_roll", Checked = true }), new EventArgs()); - chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs()); + if (MainV2.config["Tuning_Graph_Selected"] != null) + { + string line = MainV2.config["Tuning_Graph_Selected"].ToString(); + string[] lines = line.Split(new char[] { '|' }, StringSplitOptions.RemoveEmptyEntries); + foreach (string option in lines) + { + chk_box_CheckedChanged((object)(new CheckBox() { Name = option, Checked = true }), new EventArgs()); + } + } + else + { + chk_box_CheckedChanged((object)(new CheckBox() { Name = "roll", Checked = true }), new EventArgs()); + chk_box_CheckedChanged((object)(new CheckBox() { Name = "pitch", Checked = true }), new EventArgs()); + chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_roll", Checked = true }), new EventArgs()); + chk_box_CheckedChanged((object)(new CheckBox() { Name = "nav_pitch", Checked = true }), new EventArgs()); + } List list = new List(); @@ -314,6 +341,16 @@ namespace ArdupilotMega.GCSViews list4.Add(time, (float)list4item.GetValue((object)MainV2.cs, null)); if (list5item != null) list5.Add(time, (float)list5item.GetValue((object)MainV2.cs, null)); + if (list6item != null) + list6.Add(time, (float)list6item.GetValue((object)MainV2.cs, null)); + if (list7item != null) + list7.Add(time, (float)list7item.GetValue((object)MainV2.cs, null)); + if (list8item != null) + list8.Add(time, (float)list8item.GetValue((object)MainV2.cs, null)); + if (list9item != null) + list9.Add(time, (float)list9item.GetValue((object)MainV2.cs, null)); + if (list10item != null) + list10.Add(time, (float)list10item.GetValue((object)MainV2.cs, null)); } if (tracklast.AddSeconds(1) < DateTime.Now) @@ -681,14 +718,14 @@ namespace ArdupilotMega.GCSViews { if (CB_tuning.Checked) { - gMapControl1.Visible = false; + splitContainer1.Panel1Collapsed = false; ZedGraphTimer.Enabled = true; ZedGraphTimer.Start(); zg1.Visible = true; } else { - gMapControl1.Visible = true; + splitContainer1.Panel1Collapsed = true; ZedGraphTimer.Enabled = false; ZedGraphTimer.Stop(); zg1.Visible = false; @@ -1203,6 +1240,8 @@ namespace ArdupilotMega.GCSViews return; } } + + } private void zg1_DoubleClick(object sender, EventArgs e) @@ -1210,7 +1249,7 @@ namespace ArdupilotMega.GCSViews Form selectform = new Form() { Name = "select", - Width = 650, + Width = 750, Height = 250, Text = "Graph This" }; @@ -1218,6 +1257,19 @@ namespace ArdupilotMega.GCSViews int x = 10; int y = 10; + { + CheckBox chk_box = new CheckBox(); + chk_box.Text = "Logarithmic"; + chk_box.Name = "Logarithmic"; + chk_box.Location = new Point(x, y); + chk_box.Size = new System.Drawing.Size(100, 20); + chk_box.CheckedChanged += new EventHandler(chk_log_CheckedChanged); + + selectform.Controls.Add(chk_box); + } + + y += 20; + object thisBoxed = MainV2.cs; Type test = thisBoxed.GetType(); @@ -1249,6 +1301,16 @@ namespace ArdupilotMega.GCSViews chk_box.Checked = true; if (list5item != null && list5item.Name == field.Name) chk_box.Checked = true; + if (list6item != null && list6item.Name == field.Name) + chk_box.Checked = true; + if (list7item != null && list7item.Name == field.Name) + chk_box.Checked = true; + if (list8item != null && list8item.Name == field.Name) + chk_box.Checked = true; + if (list9item != null && list9item.Name == field.Name) + chk_box.Checked = true; + if (list10item != null && list10item.Name == field.Name) + chk_box.Checked = true; chk_box.Text = field.Name; chk_box.Name = field.Name; @@ -1273,6 +1335,18 @@ namespace ArdupilotMega.GCSViews selectform.Show(); } + void chk_log_CheckedChanged(object sender, EventArgs e) + { + if (((CheckBox)sender).Checked) + { + zg1.GraphPane.YAxis.Type = AxisType.Log; + } + else + { + zg1.GraphPane.YAxis.Type = AxisType.Linear; + } + } + void chk_box_CheckedChanged(object sender, EventArgs e) { if (((CheckBox)sender).Checked) @@ -1302,12 +1376,55 @@ namespace ArdupilotMega.GCSViews setupPropertyInfo(ref list5item, ((CheckBox)sender).Name, MainV2.cs); list5curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list5, Color.Yellow, SymbolType.None); } + else if (list6item == null) + { + setupPropertyInfo(ref list6item, ((CheckBox)sender).Name, MainV2.cs); + list6curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list6, Color.Magenta, SymbolType.None); + } + else if (list7item == null) + { + setupPropertyInfo(ref list7item, ((CheckBox)sender).Name, MainV2.cs); + list7curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list7, Color.Purple, SymbolType.None); + } + else if (list8item == null) + { + setupPropertyInfo(ref list8item, ((CheckBox)sender).Name, MainV2.cs); + list8curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list8, Color.LimeGreen, SymbolType.None); + } + else if (list9item == null) + { + setupPropertyInfo(ref list9item, ((CheckBox)sender).Name, MainV2.cs); + list9curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list9, Color.Cyan, SymbolType.None); + } + else if (list10item == null) + { + setupPropertyInfo(ref list10item, ((CheckBox)sender).Name, MainV2.cs); + list10curve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name, list10, Color.Violet, SymbolType.None); + } else { - MessageBox.Show("Max 5 at a time."); + MessageBox.Show("Max 10 at a time."); ((CheckBox)sender).Checked = false; } MainV2.fixtheme(this); + + string selected = ""; + try + { + selected = selected + zg1.GraphPane.CurveList[0].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[1].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[2].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[3].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[4].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[5].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[6].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[7].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[8].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[9].Label.Text + "|"; + selected = selected + zg1.GraphPane.CurveList[10].Label.Text + "|"; + } + catch { } + MainV2.config["Tuning_Graph_Selected"] = selected; } else { @@ -1336,6 +1453,31 @@ namespace ArdupilotMega.GCSViews { list5item = null; zg1.GraphPane.CurveList.Remove(list5curve); + } + if (list6item != null && list6item.Name == ((CheckBox)sender).Name) + { + list6item = null; + zg1.GraphPane.CurveList.Remove(list6curve); + } + if (list7item != null && list7item.Name == ((CheckBox)sender).Name) + { + list7item = null; + zg1.GraphPane.CurveList.Remove(list7curve); + } + if (list8item != null && list8item.Name == ((CheckBox)sender).Name) + { + list8item = null; + zg1.GraphPane.CurveList.Remove(list8curve); + } + if (list9item != null && list9item.Name == ((CheckBox)sender).Name) + { + list9item = null; + zg1.GraphPane.CurveList.Remove(list9curve); + } + if (list10item != null && list10item.Name == ((CheckBox)sender).Name) + { + list10item = null; + zg1.GraphPane.CurveList.Remove(list10curve); } } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index d44ff71539..845fa8bfd8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -134,7 +134,7 @@ Point Camera Here - 175, 70 + 175, 48 contextMenuStrip1 @@ -1083,290 +1083,68 @@ 360 + + Single + 1 - - Bottom, Left - - - NoControl - - - 10, 10 - - - 84, 13 - - - 13 - - - 0 - - - TXT_lat - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 0 - - - Bottom, Left - - - 438, 7 - - - 76, 20 - - - 69 - - - Change Zoom Level - - - Zoomlevel - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 1 - - - Bottom, Left - - - NoControl - - - 401, 10 - - - 34, 13 - - - 70 - - - Zoom - - - label1 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 2 - - - Bottom, Left - - - NoControl - - - 100, 10 - - - 84, 13 - - - 14 - - - 0 - - - TXT_long - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 3 - - - Bottom, Left - - - NoControl - - - 190, 10 - - - 64, 13 - - - 15 - - - 0 - - - TXT_alt - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 4 - - - Bottom, Left - - - True - - - NoControl - - - 325, 10 - - - 70, 17 - - - 68 - - - Auto Pan - - - Makes the map autopan based on current location - - - CHK_autopan - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 5 - - - Bottom, Left - - - True - - - NoControl - - - 260, 9 - - - 59, 17 - - - 62 - - - Tuning - - - Show the tunning graph, chowing target attitudes vs actual - - - CB_tuning - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 6 - - + Fill - - 0, 429 + + 4, 4 - - 0, 0, 0, 0 + + Horizontal - - 585, 30 + + Fill - + + 0, 0 + + + 4, 4, 4, 4 + + + 577, 210 + + + 67 + + + False + + + zg1 + + + ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 + + + splitContainer1.Panel1 + + 0 - - panel1 + + splitContainer1.Panel1 - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tableMap + + splitContainer1 - - 0 - - - NoControl - - - 7, 21 - - - 34, 13 - - - 69 - - - Vel: 0 - - - Estimated Wind Velocity - - - lbl_windvel - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - + 0 NoControl - 7, 8 + 4, 7 32, 13 @@ -1387,9 +1165,39 @@ ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - panel2 + splitContainer1.Panel2 + 0 + + + NoControl + + + 4, 20 + + + 34, 13 + + + 69 + + + Vel: 0 + + + Estimated Wind Velocity + + + lbl_windvel + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + splitContainer1.Panel2 + + 1 @@ -1402,7 +1210,7 @@ 0, 0, 0, 0 - 585, 429 + 577, 420 @@ -1559,66 +1367,288 @@ GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef - panel2 + splitContainer1.Panel2 2 - - Fill + + splitContainer1.Panel2 - - 0, 0 + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 4, 4, 4, 4 + + splitContainer1 - - 585, 429 - - - 67 - - - False - - - zg1 - - - ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 - - - panel2 - - - 3 - - - Fill - - - 0, 0 - - - 0, 0, 0, 0 - - - 585, 429 - - + 1 - - panel2 + + 577, 420 - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 210 - + + 76 + + + splitContainer1 + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tableMap - + + 0 + + + Bottom, Left + + + NoControl + + + 10, 11 + + + 84, 13 + + + 13 + + + 0 + + + TXT_lat + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 0 + + + Bottom, Left + + + 438, 8 + + + 76, 20 + + + 69 + + + Change Zoom Level + + + Zoomlevel + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 1 + + + Bottom, Left + + + NoControl + + + 401, 11 + + + 34, 13 + + + 70 + + + Zoom + + + label1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 2 + + + Bottom, Left + + + NoControl + + + 100, 11 + + + 84, 13 + + + 14 + + + 0 + + + TXT_long + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 3 + + + Bottom, Left + + + NoControl + + + 190, 11 + + + 64, 13 + + + 15 + + + 0 + + + TXT_alt + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 4 + + + Bottom, Left + + + True + + + NoControl + + + 325, 11 + + + 70, 17 + + + 68 + + + Auto Pan + + + Makes the map autopan based on current location + + + CHK_autopan + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 5 + + + Bottom, Left + + + True + + + NoControl + + + 260, 10 + + + 59, 17 + + + 62 + + + Tuning + + + Show the tunning graph, chowing target attitudes vs actual + + + CB_tuning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 6 + + + Fill + + + 1, 428 + + + 0, 0, 0, 0 + + + 583, 30 + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + 1 @@ -1649,7 +1679,7 @@ 0 - <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel2" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30" /></TableLayoutSettings> + <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> MainH.Panel2 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index f74f23eb8d..31a3bae5b3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -277,7 +277,7 @@ namespace ArdupilotMega.GCSViews cell = Commands.Rows[selectedrow].Cells[1] as DataGridViewTextBoxCell; cell.Value = 0; } - if (Commands.Columns[Param2.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][1]/*"Alt"*/)) + if (alt != -1 && Commands.Columns[Param2.Index].HeaderText.Equals(cmdParamNames[MAVLink.MAV_CMD.WAYPOINT][1]/*"Alt"*/)) { cell = Commands.Rows[selectedrow].Cells[2] as DataGridViewTextBoxCell; @@ -1719,7 +1719,7 @@ namespace ArdupilotMega.GCSViews } else { - callMeDrag(CurentRectMarker.InnerMarker.Tag.ToString(), currentMarker.Position.Lat, currentMarker.Position.Lng, 0); + callMeDrag(CurentRectMarker.InnerMarker.Tag.ToString(), currentMarker.Position.Lat, currentMarker.Position.Lng, -1); } CurentRectMarker = null; } diff --git a/Tools/ArdupilotMegaPlanner/Joystick.cs b/Tools/ArdupilotMegaPlanner/Joystick.cs index d0bbc9eed8..6f933dad57 100644 --- a/Tools/ArdupilotMegaPlanner/Joystick.cs +++ b/Tools/ArdupilotMegaPlanner/Joystick.cs @@ -47,7 +47,7 @@ namespace ArdupilotMega self = this; } - JoyChannel[] JoyChannels = new JoyChannel[5]; // we are base 1 + JoyChannel[] JoyChannels = new JoyChannel[9]; // we are base 1 JoyButton[] JoyButtons = new JoyButton[128]; // base 0 public static DeviceList getDevices() @@ -301,16 +301,22 @@ namespace ArdupilotMega ushort roll = pickchannel(1, JoyChannels[1].axis, false, JoyChannels[1].expo); ushort pitch = pickchannel(2, JoyChannels[2].axis, false, JoyChannels[2].expo); - MainV2.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500); - MainV2.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500); + if (getJoystickAxis(1) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech1 = (ushort)(BOOL_TO_SIGN(JoyChannels[1].reverse) * ((int)(pitch - 1500) - (int)(roll - 1500)) / 2 + 1500); + if (getJoystickAxis(2) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech2 = (ushort)(BOOL_TO_SIGN(JoyChannels[2].reverse) * ((int)(pitch - 1500) + (int)(roll - 1500)) / 2 + 1500); } else { - MainV2.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000); - MainV2.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000); + if (getJoystickAxis(1) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech1 = pickchannel(1, JoyChannels[1].axis, JoyChannels[1].reverse, JoyChannels[1].expo);//(ushort)(((int)state.Rz / 65.535) + 1000); + if (getJoystickAxis(2) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech2 = pickchannel(2, JoyChannels[2].axis, JoyChannels[2].reverse, JoyChannels[2].expo);//(ushort)(((int)state.Y / 65.535) + 1000); } - MainV2.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000); - MainV2.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000); + if (getJoystickAxis(3) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech3 = pickchannel(3, JoyChannels[3].axis, JoyChannels[3].reverse, JoyChannels[3].expo);//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000); + if (getJoystickAxis(4) != Joystick.joystickaxis.None) + MainV2.cs.rcoverridech4 = pickchannel(4, JoyChannels[4].axis, JoyChannels[4].reverse, JoyChannels[4].expo);//(ushort)(((int)state.X / 65.535) + 1000); foreach (JoyButton but in JoyButtons) { @@ -349,6 +355,7 @@ namespace ArdupilotMega public enum joystickaxis { None, + Pass, ARx, ARy, ARz, @@ -462,6 +469,15 @@ namespace ArdupilotMega return joystick.Caps.NumberButtons; } + public joystickaxis getJoystickAxis(int channel) + { + try + { + return JoyChannels[channel].axis; + } + catch { return joystickaxis.None; } + } + public bool isButtonPressed(int buttonno) { byte[] buts = state.GetButtons(); @@ -510,6 +526,12 @@ namespace ArdupilotMega switch (axis) { + case joystickaxis.None: + working = ushort.MaxValue / 2; + break; + case joystickaxis.Pass: + working = (int)(((float)(trim - min) / range) * ushort.MaxValue); + break; case joystickaxis.ARx: working = state.ARx; break; diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs index 015970a315..567ecfd7c9 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs @@ -53,6 +53,25 @@ this.label8 = new System.Windows.Forms.Label(); this.label9 = new System.Windows.Forms.Label(); this.timer1 = new System.Windows.Forms.Timer(this.components); + this.CHK_elevons = new System.Windows.Forms.CheckBox(); + this.revCH5 = new System.Windows.Forms.CheckBox(); + this.label10 = new System.Windows.Forms.Label(); + this.expo_ch5 = new System.Windows.Forms.TextBox(); + this.CMB_CH5 = new System.Windows.Forms.ComboBox(); + this.revCH6 = new System.Windows.Forms.CheckBox(); + this.label11 = new System.Windows.Forms.Label(); + this.expo_ch6 = new System.Windows.Forms.TextBox(); + this.CMB_CH6 = new System.Windows.Forms.ComboBox(); + this.revCH7 = new System.Windows.Forms.CheckBox(); + this.label12 = new System.Windows.Forms.Label(); + this.expo_ch7 = new System.Windows.Forms.TextBox(); + this.CMB_CH7 = new System.Windows.Forms.ComboBox(); + this.revCH8 = new System.Windows.Forms.CheckBox(); + this.label13 = new System.Windows.Forms.Label(); + this.expo_ch8 = new System.Windows.Forms.TextBox(); + this.CMB_CH8 = new System.Windows.Forms.ComboBox(); + this.BUT_detch8 = new ArdupilotMega.MyButton(); + this.horizontalProgressBar4 = new ArdupilotMega.HorizontalProgressBar(); this.BUT_detch4 = new ArdupilotMega.MyButton(); this.BUT_detch3 = new ArdupilotMega.MyButton(); this.BUT_detch2 = new ArdupilotMega.MyButton(); @@ -63,7 +82,12 @@ this.progressBar3 = new ArdupilotMega.HorizontalProgressBar(); this.progressBar2 = new ArdupilotMega.HorizontalProgressBar(); this.progressBar1 = new ArdupilotMega.HorizontalProgressBar(); - this.CHK_elevons = new System.Windows.Forms.CheckBox(); + this.BUT_detch5 = new ArdupilotMega.MyButton(); + this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar(); + this.BUT_detch6 = new ArdupilotMega.MyButton(); + this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar(); + this.BUT_detch7 = new ArdupilotMega.MyButton(); + this.horizontalProgressBar3 = new ArdupilotMega.HorizontalProgressBar(); this.SuspendLayout(); // // CMB_joysticks @@ -224,6 +248,151 @@ this.timer1.Enabled = true; this.timer1.Tick += new System.EventHandler(this.timer1_Tick); // + // CHK_elevons + // + resources.ApplyResources(this.CHK_elevons, "CHK_elevons"); + this.CHK_elevons.Name = "CHK_elevons"; + this.CHK_elevons.UseVisualStyleBackColor = true; + this.CHK_elevons.CheckedChanged += new System.EventHandler(this.CHK_elevons_CheckedChanged); + // + // revCH5 + // + resources.ApplyResources(this.revCH5, "revCH5"); + this.revCH5.Name = "revCH5"; + this.revCH5.UseVisualStyleBackColor = true; + this.revCH5.CheckedChanged += new System.EventHandler(this.revCH5_CheckedChanged); + // + // label10 + // + resources.ApplyResources(this.label10, "label10"); + this.label10.Name = "label10"; + // + // expo_ch5 + // + this.expo_ch5.BorderStyle = System.Windows.Forms.BorderStyle.None; + resources.ApplyResources(this.expo_ch5, "expo_ch5"); + this.expo_ch5.Name = "expo_ch5"; + // + // CMB_CH5 + // + this.CMB_CH5.FormattingEnabled = true; + this.CMB_CH5.Items.AddRange(new object[] { + resources.GetString("CMB_CH5.Items"), + resources.GetString("CMB_CH5.Items1"), + resources.GetString("CMB_CH5.Items2"), + resources.GetString("CMB_CH5.Items3")}); + resources.ApplyResources(this.CMB_CH5, "CMB_CH5"); + this.CMB_CH5.Name = "CMB_CH5"; + this.CMB_CH5.SelectedIndexChanged += new System.EventHandler(this.CMB_CH5_SelectedIndexChanged); + // + // revCH6 + // + resources.ApplyResources(this.revCH6, "revCH6"); + this.revCH6.Name = "revCH6"; + this.revCH6.UseVisualStyleBackColor = true; + this.revCH6.CheckedChanged += new System.EventHandler(this.revCH6_CheckedChanged); + // + // label11 + // + resources.ApplyResources(this.label11, "label11"); + this.label11.Name = "label11"; + // + // expo_ch6 + // + this.expo_ch6.BorderStyle = System.Windows.Forms.BorderStyle.None; + resources.ApplyResources(this.expo_ch6, "expo_ch6"); + this.expo_ch6.Name = "expo_ch6"; + // + // CMB_CH6 + // + this.CMB_CH6.FormattingEnabled = true; + this.CMB_CH6.Items.AddRange(new object[] { + resources.GetString("CMB_CH6.Items"), + resources.GetString("CMB_CH6.Items1"), + resources.GetString("CMB_CH6.Items2"), + resources.GetString("CMB_CH6.Items3")}); + resources.ApplyResources(this.CMB_CH6, "CMB_CH6"); + this.CMB_CH6.Name = "CMB_CH6"; + this.CMB_CH6.SelectedIndexChanged += new System.EventHandler(this.CMB_CH6_SelectedIndexChanged); + // + // revCH7 + // + resources.ApplyResources(this.revCH7, "revCH7"); + this.revCH7.Name = "revCH7"; + this.revCH7.UseVisualStyleBackColor = true; + this.revCH7.CheckedChanged += new System.EventHandler(this.revCH7_CheckedChanged); + // + // label12 + // + resources.ApplyResources(this.label12, "label12"); + this.label12.Name = "label12"; + // + // expo_ch7 + // + this.expo_ch7.BorderStyle = System.Windows.Forms.BorderStyle.None; + resources.ApplyResources(this.expo_ch7, "expo_ch7"); + this.expo_ch7.Name = "expo_ch7"; + // + // CMB_CH7 + // + this.CMB_CH7.FormattingEnabled = true; + this.CMB_CH7.Items.AddRange(new object[] { + resources.GetString("CMB_CH7.Items"), + resources.GetString("CMB_CH7.Items1"), + resources.GetString("CMB_CH7.Items2"), + resources.GetString("CMB_CH7.Items3")}); + resources.ApplyResources(this.CMB_CH7, "CMB_CH7"); + this.CMB_CH7.Name = "CMB_CH7"; + this.CMB_CH7.SelectedIndexChanged += new System.EventHandler(this.CMB_CH7_SelectedIndexChanged); + // + // revCH8 + // + resources.ApplyResources(this.revCH8, "revCH8"); + this.revCH8.Name = "revCH8"; + this.revCH8.UseVisualStyleBackColor = true; + this.revCH8.CheckedChanged += new System.EventHandler(this.revCH8_CheckedChanged); + // + // label13 + // + resources.ApplyResources(this.label13, "label13"); + this.label13.Name = "label13"; + // + // expo_ch8 + // + this.expo_ch8.BorderStyle = System.Windows.Forms.BorderStyle.None; + resources.ApplyResources(this.expo_ch8, "expo_ch8"); + this.expo_ch8.Name = "expo_ch8"; + // + // CMB_CH8 + // + this.CMB_CH8.FormattingEnabled = true; + this.CMB_CH8.Items.AddRange(new object[] { + resources.GetString("CMB_CH8.Items"), + resources.GetString("CMB_CH8.Items1"), + resources.GetString("CMB_CH8.Items2"), + resources.GetString("CMB_CH8.Items3")}); + resources.ApplyResources(this.CMB_CH8, "CMB_CH8"); + this.CMB_CH8.Name = "CMB_CH8"; + this.CMB_CH8.SelectedIndexChanged += new System.EventHandler(this.CMB_CH8_SelectedIndexChanged); + // + // BUT_detch8 + // + resources.ApplyResources(this.BUT_detch8, "BUT_detch8"); + this.BUT_detch8.Name = "BUT_detch8"; + this.BUT_detch8.UseVisualStyleBackColor = true; + this.BUT_detch8.Click += new System.EventHandler(this.BUT_detch8_Click); + // + // horizontalProgressBar4 + // + resources.ApplyResources(this.horizontalProgressBar4, "horizontalProgressBar4"); + this.horizontalProgressBar4.Label = null; + this.horizontalProgressBar4.Maximum = 2200; + this.horizontalProgressBar4.maxline = 0; + this.horizontalProgressBar4.Minimum = 800; + this.horizontalProgressBar4.minline = 0; + this.horizontalProgressBar4.Name = "horizontalProgressBar4"; + this.horizontalProgressBar4.Value = 800; + // // BUT_detch4 // resources.ApplyResources(this.BUT_detch4, "BUT_detch4"); @@ -310,17 +479,88 @@ this.progressBar1.Name = "progressBar1"; this.progressBar1.Value = 800; // - // CHK_elevons + // BUT_detch5 // - resources.ApplyResources(this.CHK_elevons, "CHK_elevons"); - this.CHK_elevons.Name = "CHK_elevons"; - this.CHK_elevons.UseVisualStyleBackColor = true; - this.CHK_elevons.CheckedChanged += new System.EventHandler(this.CHK_elevons_CheckedChanged); + resources.ApplyResources(this.BUT_detch5, "BUT_detch5"); + this.BUT_detch5.Name = "BUT_detch5"; + this.BUT_detch5.UseVisualStyleBackColor = true; + this.BUT_detch5.Click += new System.EventHandler(this.BUT_detch5_Click); + // + // horizontalProgressBar1 + // + resources.ApplyResources(this.horizontalProgressBar1, "horizontalProgressBar1"); + this.horizontalProgressBar1.Label = null; + this.horizontalProgressBar1.Maximum = 2200; + this.horizontalProgressBar1.maxline = 0; + this.horizontalProgressBar1.Minimum = 800; + this.horizontalProgressBar1.minline = 0; + this.horizontalProgressBar1.Name = "horizontalProgressBar1"; + this.horizontalProgressBar1.Value = 800; + // + // BUT_detch6 + // + resources.ApplyResources(this.BUT_detch6, "BUT_detch6"); + this.BUT_detch6.Name = "BUT_detch6"; + this.BUT_detch6.UseVisualStyleBackColor = true; + this.BUT_detch6.Click += new System.EventHandler(this.BUT_detch6_Click); + // + // horizontalProgressBar2 + // + resources.ApplyResources(this.horizontalProgressBar2, "horizontalProgressBar2"); + this.horizontalProgressBar2.Label = null; + this.horizontalProgressBar2.Maximum = 2200; + this.horizontalProgressBar2.maxline = 0; + this.horizontalProgressBar2.Minimum = 800; + this.horizontalProgressBar2.minline = 0; + this.horizontalProgressBar2.Name = "horizontalProgressBar2"; + this.horizontalProgressBar2.Value = 800; + // + // BUT_detch7 + // + resources.ApplyResources(this.BUT_detch7, "BUT_detch7"); + this.BUT_detch7.Name = "BUT_detch7"; + this.BUT_detch7.UseVisualStyleBackColor = true; + this.BUT_detch7.Click += new System.EventHandler(this.BUT_detch7_Click); + // + // horizontalProgressBar3 + // + resources.ApplyResources(this.horizontalProgressBar3, "horizontalProgressBar3"); + this.horizontalProgressBar3.Label = null; + this.horizontalProgressBar3.Maximum = 2200; + this.horizontalProgressBar3.maxline = 0; + this.horizontalProgressBar3.Minimum = 800; + this.horizontalProgressBar3.minline = 0; + this.horizontalProgressBar3.Name = "horizontalProgressBar3"; + this.horizontalProgressBar3.Value = 800; // // JoystickSetup // resources.ApplyResources(this, "$this"); this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font; + this.Controls.Add(this.BUT_detch8); + this.Controls.Add(this.revCH8); + this.Controls.Add(this.label13); + this.Controls.Add(this.expo_ch8); + this.Controls.Add(this.horizontalProgressBar4); + this.Controls.Add(this.CMB_CH8); + this.Controls.Add(this.BUT_detch7); + this.Controls.Add(this.revCH7); + this.Controls.Add(this.label12); + this.Controls.Add(this.expo_ch7); + this.Controls.Add(this.horizontalProgressBar3); + this.Controls.Add(this.CMB_CH7); + this.Controls.Add(this.BUT_detch6); + this.Controls.Add(this.revCH6); + this.Controls.Add(this.label11); + this.Controls.Add(this.expo_ch6); + this.Controls.Add(this.horizontalProgressBar2); + this.Controls.Add(this.CMB_CH6); + this.Controls.Add(this.BUT_detch5); + this.Controls.Add(this.revCH5); + this.Controls.Add(this.label10); + this.Controls.Add(this.expo_ch5); + this.Controls.Add(this.horizontalProgressBar1); + this.Controls.Add(this.CMB_CH5); this.Controls.Add(this.CHK_elevons); this.Controls.Add(this.BUT_detch4); this.Controls.Add(this.BUT_detch3); @@ -398,5 +638,29 @@ private MyButton BUT_detch3; private MyButton BUT_detch4; private System.Windows.Forms.CheckBox CHK_elevons; + private MyButton BUT_detch5; + private System.Windows.Forms.CheckBox revCH5; + private System.Windows.Forms.Label label10; + private System.Windows.Forms.TextBox expo_ch5; + private HorizontalProgressBar horizontalProgressBar1; + private System.Windows.Forms.ComboBox CMB_CH5; + private MyButton BUT_detch6; + private System.Windows.Forms.CheckBox revCH6; + private System.Windows.Forms.Label label11; + private System.Windows.Forms.TextBox expo_ch6; + private HorizontalProgressBar horizontalProgressBar2; + private System.Windows.Forms.ComboBox CMB_CH6; + private MyButton BUT_detch7; + private System.Windows.Forms.CheckBox revCH7; + private System.Windows.Forms.Label label12; + private System.Windows.Forms.TextBox expo_ch7; + private HorizontalProgressBar horizontalProgressBar3; + private System.Windows.Forms.ComboBox CMB_CH7; + private MyButton BUT_detch8; + private System.Windows.Forms.CheckBox revCH8; + private System.Windows.Forms.Label label13; + private System.Windows.Forms.TextBox expo_ch8; + private HorizontalProgressBar horizontalProgressBar4; + private System.Windows.Forms.ComboBox CMB_CH8; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs index d5e8be68cc..7548c4935a 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs @@ -43,6 +43,10 @@ namespace ArdupilotMega CMB_CH2.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH3.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); CMB_CH4.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); + CMB_CH5.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); + CMB_CH6.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); + CMB_CH7.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); + CMB_CH8.DataSource = (Enum.GetValues(typeof(Joystick.joystickaxis))); try { @@ -51,18 +55,30 @@ namespace ArdupilotMega CMB_CH2.Text = MainV2.config["CMB_CH2"].ToString(); CMB_CH3.Text = MainV2.config["CMB_CH3"].ToString(); CMB_CH4.Text = MainV2.config["CMB_CH4"].ToString(); + CMB_CH5.Text = MainV2.config["CMB_CH5"].ToString(); + CMB_CH6.Text = MainV2.config["CMB_CH6"].ToString(); + CMB_CH7.Text = MainV2.config["CMB_CH7"].ToString(); + CMB_CH8.Text = MainV2.config["CMB_CH8"].ToString(); //revCH1 revCH1.Checked = bool.Parse(MainV2.config["revCH1"].ToString()); revCH2.Checked = bool.Parse(MainV2.config["revCH2"].ToString()); revCH3.Checked = bool.Parse(MainV2.config["revCH3"].ToString()); revCH4.Checked = bool.Parse(MainV2.config["revCH4"].ToString()); + revCH5.Checked = bool.Parse(MainV2.config["revCH5"].ToString()); + revCH6.Checked = bool.Parse(MainV2.config["revCH6"].ToString()); + revCH7.Checked = bool.Parse(MainV2.config["revCH7"].ToString()); + revCH8.Checked = bool.Parse(MainV2.config["revCH8"].ToString()); //expo_ch1 expo_ch1.Text = MainV2.config["expo_ch1"].ToString(); expo_ch2.Text = MainV2.config["expo_ch2"].ToString(); expo_ch3.Text = MainV2.config["expo_ch3"].ToString(); expo_ch4.Text = MainV2.config["expo_ch4"].ToString(); + expo_ch5.Text = MainV2.config["expo_ch5"].ToString(); + expo_ch6.Text = MainV2.config["expo_ch6"].ToString(); + expo_ch7.Text = MainV2.config["expo_ch7"].ToString(); + expo_ch8.Text = MainV2.config["expo_ch8"].ToString(); CHK_elevons.Checked = bool.Parse(MainV2.config["joy_elevons"].ToString()); } @@ -104,6 +120,10 @@ namespace ArdupilotMega joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text)); joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text)); joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text)); + joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text)); + joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text)); + joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text)); + joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text)); joy.elevons = CHK_elevons.Checked; @@ -153,13 +173,6 @@ namespace ArdupilotMega MainV2.joystick = null; BUT_enable.Text = "Enable"; } - - /* - MainV2.cs.rcoverridech1 = pickchannel(1, CMB_CH1.Text, revCH1.Checked, int.Parse(expo_ch1.Text));//(ushort)(((int)state.Rz / 65.535) + 1000); - MainV2.cs.rcoverridech2 = pickchannel(2, CMB_CH2.Text, revCH2.Checked, int.Parse(expo_ch2.Text));//(ushort)(((int)state.Y / 65.535) + 1000); - MainV2.cs.rcoverridech3 = pickchannel(3, CMB_CH3.Text, revCH3.Checked, int.Parse(expo_ch3.Text));//(ushort)(1000 - ((int)slider[0] / 65.535) + 1000); - MainV2.cs.rcoverridech4 = pickchannel(4, CMB_CH4.Text, revCH4.Checked, int.Parse(expo_ch4.Text));//(ushort)(((int)state.X / 65.535) + 1000); - */ } private void BUT_save_Click(object sender, EventArgs e) @@ -169,18 +182,30 @@ namespace ArdupilotMega MainV2.config["CMB_CH2"] = CMB_CH2.Text; MainV2.config["CMB_CH3"] = CMB_CH3.Text; MainV2.config["CMB_CH4"] = CMB_CH4.Text; + MainV2.config["CMB_CH5"] = CMB_CH5.Text; + MainV2.config["CMB_CH6"] = CMB_CH6.Text; + MainV2.config["CMB_CH7"] = CMB_CH7.Text; + MainV2.config["CMB_CH8"] = CMB_CH8.Text; //revCH1 MainV2.config["revCH1"] = revCH1.Checked; MainV2.config["revCH2"] = revCH2.Checked; MainV2.config["revCH3"] = revCH3.Checked; MainV2.config["revCH4"] = revCH4.Checked; + MainV2.config["revCH5"] = revCH5.Checked; + MainV2.config["revCH6"] = revCH6.Checked; + MainV2.config["revCH7"] = revCH7.Checked; + MainV2.config["revCH8"] = revCH8.Checked; //expo_ch1 MainV2.config["expo_ch1"] = expo_ch1.Text; MainV2.config["expo_ch2"] = expo_ch2.Text; MainV2.config["expo_ch3"] = expo_ch3.Text; MainV2.config["expo_ch4"] = expo_ch4.Text; + MainV2.config["expo_ch5"] = expo_ch5.Text; + MainV2.config["expo_ch6"] = expo_ch6.Text; + MainV2.config["expo_ch7"] = expo_ch7.Text; + MainV2.config["expo_ch8"] = expo_ch8.Text; MainV2.config["joy_elevons"] = CHK_elevons.Checked; @@ -207,6 +232,10 @@ namespace ArdupilotMega joy.setChannel(2, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH2.Text), revCH2.Checked, int.Parse(expo_ch2.Text)); joy.setChannel(3, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH3.Text), revCH3.Checked, int.Parse(expo_ch3.Text)); joy.setChannel(4, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH4.Text), revCH4.Checked, int.Parse(expo_ch4.Text)); + joy.setChannel(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH5.Text), revCH5.Checked, int.Parse(expo_ch5.Text)); + joy.setChannel(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH6.Text), revCH6.Checked, int.Parse(expo_ch6.Text)); + joy.setChannel(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH7.Text), revCH7.Checked, int.Parse(expo_ch7.Text)); + joy.setChannel(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), CMB_CH8.Text), revCH8.Checked, int.Parse(expo_ch8.Text)); joy.elevons = CHK_elevons.Checked; @@ -218,7 +247,7 @@ namespace ArdupilotMega { string name = (f + 1).ToString(); - doButtontoUI(name, 10, 195 + f * 25); + doButtontoUI(name, 10, 290 + f * 25); joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text); } @@ -236,6 +265,10 @@ namespace ArdupilotMega MainV2.cs.rcoverridech2 = joy.getValueForChannel(2, CMB_joysticks.Text); MainV2.cs.rcoverridech3 = joy.getValueForChannel(3, CMB_joysticks.Text); MainV2.cs.rcoverridech4 = joy.getValueForChannel(4, CMB_joysticks.Text); + MainV2.cs.rcoverridech5 = joy.getValueForChannel(5, CMB_joysticks.Text); + MainV2.cs.rcoverridech6 = joy.getValueForChannel(6, CMB_joysticks.Text); + MainV2.cs.rcoverridech7 = joy.getValueForChannel(7, CMB_joysticks.Text); + MainV2.cs.rcoverridech8 = joy.getValueForChannel(8, CMB_joysticks.Text); //Console.WriteLine(DateTime.Now.Millisecond + " end "); } @@ -246,6 +279,10 @@ namespace ArdupilotMega progressBar2.Value = MainV2.cs.rcoverridech2; progressBar3.Value = MainV2.cs.rcoverridech3; progressBar4.Value = MainV2.cs.rcoverridech4; + horizontalProgressBar1.Value = MainV2.cs.rcoverridech5; + horizontalProgressBar2.Value = MainV2.cs.rcoverridech6; + horizontalProgressBar3.Value = MainV2.cs.rcoverridech7; + horizontalProgressBar4.Value = MainV2.cs.rcoverridech8; try { @@ -432,5 +469,77 @@ namespace ArdupilotMega { MainV2.joystick.elevons = CHK_elevons.Checked; } + + private void CMB_CH5_SelectedIndexChanged(object sender, EventArgs e) + { + if (startup || MainV2.joystick == null) + return; + MainV2.joystick.setAxis(5, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text)); + } + + private void CMB_CH6_SelectedIndexChanged(object sender, EventArgs e) + { + if (startup || MainV2.joystick == null) + return; + MainV2.joystick.setAxis(6, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text)); + } + + private void CMB_CH7_SelectedIndexChanged(object sender, EventArgs e) + { + if (startup || MainV2.joystick == null) + return; + MainV2.joystick.setAxis(7, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text)); + } + + private void CMB_CH8_SelectedIndexChanged(object sender, EventArgs e) + { + if (startup || MainV2.joystick == null) + return; + MainV2.joystick.setAxis(8, (Joystick.joystickaxis)Enum.Parse(typeof(Joystick.joystickaxis), ((ComboBox)sender).Text)); + } + + private void BUT_detch5_Click(object sender, EventArgs e) + { + CMB_CH5.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString(); + } + + private void BUT_detch6_Click(object sender, EventArgs e) + { + CMB_CH6.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString(); + } + + private void BUT_detch7_Click(object sender, EventArgs e) + { + CMB_CH7.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString(); + } + + private void BUT_detch8_Click(object sender, EventArgs e) + { + CMB_CH8.Text = Joystick.getMovingAxis(CMB_joysticks.Text, 16000).ToString(); + } + + private void revCH5_CheckedChanged(object sender, EventArgs e) + { + if (MainV2.joystick != null) + MainV2.joystick.setReverse(5, ((CheckBox)sender).Checked); + } + + private void revCH6_CheckedChanged(object sender, EventArgs e) + { + if (MainV2.joystick != null) + MainV2.joystick.setReverse(6, ((CheckBox)sender).Checked); + } + + private void revCH7_CheckedChanged(object sender, EventArgs e) + { + if (MainV2.joystick != null) + MainV2.joystick.setReverse(7, ((CheckBox)sender).Checked); + } + + private void revCH8_CheckedChanged(object sender, EventArgs e) + { + if (MainV2.joystick != null) + MainV2.joystick.setReverse(8, ((CheckBox)sender).Checked); + } } } diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx index eccf946e39..9b38147048 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx @@ -138,7 +138,7 @@ $this - 32 + 56 RZ @@ -171,7 +171,7 @@ $this - 31 + 55 RZ @@ -204,7 +204,7 @@ $this - 30 + 54 RZ @@ -237,7 +237,7 @@ $this - 29 + 53 RZ @@ -270,7 +270,7 @@ $this - 28 + 52 307, 70 @@ -294,7 +294,7 @@ $this - 23 + 47 307, 97 @@ -318,7 +318,7 @@ $this - 22 + 46 False @@ -345,7 +345,7 @@ $this - 21 + 45 307, 151 @@ -369,7 +369,7 @@ $this - 20 + 44 True @@ -400,7 +400,7 @@ $this - 19 + 43 True @@ -430,7 +430,7 @@ $this - 18 + 42 True @@ -460,7 +460,7 @@ $this - 17 + 41 True @@ -490,7 +490,7 @@ $this - 16 + 40 True @@ -517,7 +517,7 @@ $this - 15 + 39 True @@ -544,7 +544,7 @@ $this - 14 + 38 True @@ -571,7 +571,7 @@ $this - 13 + 37 True @@ -598,7 +598,7 @@ $this - 12 + 36 True @@ -628,7 +628,7 @@ $this - 9 + 33 True @@ -658,7 +658,7 @@ $this - 8 + 32 True @@ -688,7 +688,7 @@ $this - 7 + 31 True @@ -718,7 +718,7 @@ $this - 6 + 30 True @@ -748,11 +748,548 @@ $this - 5 + 29 17, 17 + + True + + + NoControl + + + 434, 81 + + + 64, 17 + + + 32 + + + Elevons + + + CHK_elevons + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + True + + + NoControl + + + 413, 179 + + + 15, 14 + + + 37 + + + revCH5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + NoControl + + + 9, 181 + + + 31, 13 + + + 36 + + + CH 5 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 307, 180 + + + 100, 13 + + + 35 + + + 0 + + + expo_ch5 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 176 + + + 70, 21 + + + 33 + + + CMB_CH5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + NoControl + + + 413, 208 + + + 15, 14 + + + 43 + + + revCH6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + True + + + NoControl + + + 9, 210 + + + 31, 13 + + + 42 + + + CH 6 + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 307, 209 + + + 100, 13 + + + 41 + + + 0 + + + expo_ch6 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 205 + + + 70, 21 + + + 39 + + + CMB_CH6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + NoControl + + + 413, 237 + + + 15, 14 + + + 49 + + + revCH7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + NoControl + + + 9, 239 + + + 31, 13 + + + 48 + + + CH 7 + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 307, 238 + + + 100, 13 + + + 47 + + + 0 + + + expo_ch7 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 234 + + + 70, 21 + + + 45 + + + CMB_CH7 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + NoControl + + + 413, 266 + + + 15, 14 + + + 55 + + + revCH8 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 9, 268 + + + 31, 13 + + + 54 + + + CH 8 + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 307, 267 + + + 100, 13 + + + 53 + + + 0 + + + expo_ch8 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 263 + + + 70, 21 + + + 51 + + + CMB_CH8 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + NoControl + + + 148, 263 + + + 45, 23 + + + 56 + + + Auto Detect + + + BUT_detch8 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 0 + + + NoControl + + + 199, 262 + + + 100, 23 + + + 52 + + + horizontalProgressBar4 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 4 + NoControl @@ -778,7 +1315,7 @@ $this - 1 + 25 NoControl @@ -805,7 +1342,7 @@ $this - 2 + 26 NoControl @@ -832,7 +1369,7 @@ $this - 3 + 27 NoControl @@ -859,7 +1396,7 @@ $this - 4 + 28 NoControl @@ -886,7 +1423,7 @@ $this - 10 + 34 NoControl @@ -913,7 +1450,7 @@ $this - 11 + 35 NoControl @@ -937,7 +1474,7 @@ $this - 24 + 48 NoControl @@ -961,7 +1498,7 @@ $this - 25 + 49 NoControl @@ -985,7 +1522,7 @@ $this - 26 + 50 NoControl @@ -1009,34 +1546,160 @@ $this - 27 + 51 - - True + + NoControl - - 434, 81 + + 148, 176 - - 64, 17 + + 45, 23 - - 32 + + 38 - - Elevons + + Auto Detect - - CHK_elevons + + BUT_detch5 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - + $this - - 0 + + 18 + + + NoControl + + + 199, 175 + + + 100, 23 + + + 34 + + + horizontalProgressBar1 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 22 + + + NoControl + + + 148, 205 + + + 45, 23 + + + 44 + + + Auto Detect + + + BUT_detch6 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 12 + + + NoControl + + + 199, 204 + + + 100, 23 + + + 40 + + + horizontalProgressBar2 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 16 + + + NoControl + + + 148, 234 + + + 45, 23 + + + 50 + + + Auto Detect + + + BUT_detch7 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 6 + + + NoControl + + + 199, 233 + + + 100, 23 + + + 46 + + + horizontalProgressBar3 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 10 True @@ -1045,7 +1708,7 @@ 6, 13 - 498, 220 + 498, 331 diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index 01b198c91c..6399558128 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -23,11 +23,11 @@ namespace ArdupilotMega public byte sysid = 0; public byte compid = 0; public Hashtable param = new Hashtable(); - public static byte[][] packets = new byte[256][]; + public byte[][] packets = new byte[256][]; public double[] packetspersecond = new double[256]; DateTime[] packetspersecondbuild = new DateTime[256]; - static object objlock = new object(); - static object readlock = new object(); + object objlock = new object(); + object readlock = new object(); object logwritelock = new object(); public DateTime lastvalidpacket = DateTime.Now; bool oldlogformat = false; @@ -44,7 +44,7 @@ namespace ArdupilotMega public BinaryReader logplaybackfile = null; public BinaryWriter logfile = null; - public static byte[] streams = new byte[256]; + public byte[] streams = new byte[256]; int bps1 = 0; int bps2 = 0; diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index fc89344aea..bb8034b729 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -66,10 +66,10 @@ namespace ArdupilotMega GCSViews.FlightData FlightData; GCSViews.FlightPlanner FlightPlanner; - //GCSViews.Configuration Configuration; + GCSViews.Configuration Configuration; GCSViews.Simulation Simulation; GCSViews.Firmware Firmware; - //GCSViews.Terminal Terminal; + GCSViews.Terminal Terminal; public MainV2() { @@ -221,6 +221,22 @@ namespace ArdupilotMega splash.Close(); } + internal void ScreenShot() + { + Rectangle bounds = Screen.GetBounds(Point.Empty); + using (Bitmap bitmap = new Bitmap(bounds.Width, bounds.Height)) + { + using (Graphics g = Graphics.FromImage(bitmap)) + { + g.CopyFromScreen(Point.Empty, Point.Empty, bounds.Size); + } + string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg"; + bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg); + MessageBox.Show("Screenshot saved to " + name); + } + + } + private void CMB_serialport_Click(object sender, EventArgs e) { string oldport = CMB_serialport.Text; @@ -456,7 +472,19 @@ namespace ArdupilotMega GCSViews.Terminal.threadrun = false; - UserControl temp = new GCSViews.Configuration(); + // dispose of old else memory leak + if (Configuration != null) + { + try + { + Configuration.Dispose(); + } + catch { } + } + + Configuration = new GCSViews.Configuration(); + + UserControl temp = Configuration; temp.SuspendLayout(); @@ -633,6 +661,8 @@ namespace ArdupilotMega cs.firmware = APMFirmware; + config[CMB_serialport.Text + "_BAUD"] = CMB_baudrate.Text; + if (config["loadwpsonconnect"] != null && bool.Parse(config["loadwpsonconnect"].ToString()) == true) { MenuFlightPlanner_Click(null, null); @@ -697,6 +727,9 @@ namespace ArdupilotMega try { comPort.BaseStream.PortName = CMB_serialport.Text; + + if (config[CMB_serialport.Text + "_BAUD"] != null) + CMB_baudrate.Text = config[CMB_serialport.Text + "_BAUD"].ToString(); } catch { } } @@ -874,10 +907,22 @@ namespace ArdupilotMega rc.target_component = comPort.compid; rc.target_system = comPort.sysid; - rc.chan1_raw = cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000); - rc.chan2_raw = cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000); - rc.chan3_raw = cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000); - rc.chan4_raw = cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000); + if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None) + rc.chan1_raw = cs.rcoverridech1;//(ushort)(((int)state.Rz / 65.535) + 1000); + if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None) + rc.chan2_raw = cs.rcoverridech2;//(ushort)(((int)state.Y / 65.535) + 1000); + if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None) + rc.chan3_raw = cs.rcoverridech3;//(ushort)(1000 - ((int)slider[0] / 65.535 ) + 1000); + if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None) + rc.chan4_raw = cs.rcoverridech4;//(ushort)(((int)state.X / 65.535) + 1000); + if (joystick.getJoystickAxis(5) != Joystick.joystickaxis.None) + rc.chan5_raw = cs.rcoverridech5; + if (joystick.getJoystickAxis(6) != Joystick.joystickaxis.None) + rc.chan6_raw = cs.rcoverridech6; + if (joystick.getJoystickAxis(7) != Joystick.joystickaxis.None) + rc.chan7_raw = cs.rcoverridech7; + if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None) + rc.chan8_raw = cs.rcoverridech8; if (lastjoystick.AddMilliseconds(50) < DateTime.Now) { @@ -1545,6 +1590,11 @@ namespace ArdupilotMega frm.Show(); return true; } + if (keyData == (Keys.Control | Keys.S)) + { + ScreenShot(); + return true; + } if (keyData == (Keys.Control | Keys.G)) // test { Form frm = new SerialOutput(); diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs index 8f357122d7..7be69fa57d 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs @@ -137,7 +137,7 @@ namespace ArdupilotMega flyto.Duration = (cs.datetime - lasttime).TotalMilliseconds / 1000.0; flyto.Mode = FlyToMode.Smooth; - Camera cam = new Camera(); + SharpKml.Dom.Camera cam = new SharpKml.Dom.Camera(); cam.AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute; cam.Latitude = cs.lat; cam.Longitude = cs.lng; @@ -316,7 +316,7 @@ namespace ArdupilotMega mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); mine.logreadmode = true; - MAVLink.packets.Initialize(); // clear + mine.packets.Initialize(); // clear CurrentState cs = new CurrentState(); @@ -422,7 +422,7 @@ namespace ArdupilotMega mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read)); mine.logreadmode = true; - MAVLink.packets.Initialize(); // clear + mine.packets.Initialize(); // clear StreamWriter sw = new StreamWriter(Path.GetDirectoryName(logfile)+ Path.DirectorySeparatorChar + Path.GetFileNameWithoutExtension(logfile) + ".txt"); diff --git a/Tools/ArdupilotMegaPlanner/Program.cs b/Tools/ArdupilotMegaPlanner/Program.cs index f45c622cca..148f07202c 100644 --- a/Tools/ArdupilotMegaPlanner/Program.cs +++ b/Tools/ArdupilotMegaPlanner/Program.cs @@ -24,6 +24,7 @@ namespace ArdupilotMega Application.EnableVisualStyles(); Application.SetCompatibleTextRenderingDefault(false); + //Application.Run(new Camera()); Application.Run(new MainV2()); } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index f9d0b01b3a..f5bdf0e072 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.0.84")] +[assembly: AssemblyFileVersion("1.0.86")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/SerialOutput.cs b/Tools/ArdupilotMegaPlanner/SerialOutput.cs index ee08026c8b..57f0bbe2e2 100644 --- a/Tools/ArdupilotMegaPlanner/SerialOutput.cs +++ b/Tools/ArdupilotMegaPlanner/SerialOutput.cs @@ -14,7 +14,8 @@ namespace ArdupilotMega { System.Threading.Thread t12; static bool threadrun = false; - static SerialPort comPort = new SerialPort(); + static internal SerialPort comPort = new SerialPort(); + static internal PointLatLngAlt HomeLoc = new PointLatLngAlt(0,0,0,"Home"); public SerialOutput() { @@ -62,6 +63,7 @@ namespace ArdupilotMega void mainloop() { threadrun = true; + int counter = 0; while (threadrun) { try @@ -78,7 +80,16 @@ namespace ArdupilotMega checksum = GetChecksum(line); comPort.WriteLine(line + "*" + checksum); + if (counter % 5 == 0 && HomeLoc.Lat != 0 && HomeLoc.Lng != 0) + { + line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},", "HOM", DateTime.Now.ToUniversalTime(), Math.Abs(HomeLoc.Lat * 100), HomeLoc.Lat < 0 ? "S" : "N", Math.Abs(HomeLoc.Lng * 100), HomeLoc.Lng < 0 ? "W" : "E", HomeLoc.Alt, "M"); + + checksum = GetChecksum(line); + comPort.WriteLine(line + "*" + checksum); + } + System.Threading.Thread.Sleep(500); + counter++; } catch { } } diff --git a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj index 90999833b9..8b7bd960df 100644 --- a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj +++ b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj @@ -53,7 +53,7 @@ - true + false mykey.pfx diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application index cb43d874f2..83424ad35a 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application +++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application @@ -11,7 +11,7 @@ - sVd4w+f3LroCsyok5UsAi4Bq9eI= + FgyYFBDKA+EmX+ZazsEdbI/ME7o= diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightData.resx index d44ff71539..845fa8bfd8 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/bin/Release/GCSViews/FlightData.resx @@ -134,7 +134,7 @@ Point Camera Here - 175, 70 + 175, 48 contextMenuStrip1 @@ -1083,290 +1083,68 @@ 360 + + Single + 1 - - Bottom, Left - - - NoControl - - - 10, 10 - - - 84, 13 - - - 13 - - - 0 - - - TXT_lat - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 0 - - - Bottom, Left - - - 438, 7 - - - 76, 20 - - - 69 - - - Change Zoom Level - - - Zoomlevel - - - System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 1 - - - Bottom, Left - - - NoControl - - - 401, 10 - - - 34, 13 - - - 70 - - - Zoom - - - label1 - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 2 - - - Bottom, Left - - - NoControl - - - 100, 10 - - - 84, 13 - - - 14 - - - 0 - - - TXT_long - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 3 - - - Bottom, Left - - - NoControl - - - 190, 10 - - - 64, 13 - - - 15 - - - 0 - - - TXT_alt - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel1 - - - 4 - - - Bottom, Left - - - True - - - NoControl - - - 325, 10 - - - 70, 17 - - - 68 - - - Auto Pan - - - Makes the map autopan based on current location - - - CHK_autopan - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 5 - - - Bottom, Left - - - True - - - NoControl - - - 260, 9 - - - 59, 17 - - - 62 - - - Tuning - - - Show the tunning graph, chowing target attitudes vs actual - - - CB_tuning - - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - panel1 - - - 6 - - + Fill - - 0, 429 + + 4, 4 - - 0, 0, 0, 0 + + Horizontal - - 585, 30 + + Fill - + + 0, 0 + + + 4, 4, 4, 4 + + + 577, 210 + + + 67 + + + False + + + zg1 + + + ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 + + + splitContainer1.Panel1 + + 0 - - panel1 + + splitContainer1.Panel1 - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - tableMap + + splitContainer1 - - 0 - - - NoControl - - - 7, 21 - - - 34, 13 - - - 69 - - - Vel: 0 - - - Estimated Wind Velocity - - - lbl_windvel - - - ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - - - panel2 - - + 0 NoControl - 7, 8 + 4, 7 32, 13 @@ -1387,9 +1165,39 @@ ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - panel2 + splitContainer1.Panel2 + 0 + + + NoControl + + + 4, 20 + + + 34, 13 + + + 69 + + + Vel: 0 + + + Estimated Wind Velocity + + + lbl_windvel + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + splitContainer1.Panel2 + + 1 @@ -1402,7 +1210,7 @@ 0, 0, 0, 0 - 585, 429 + 577, 420 @@ -1559,66 +1367,288 @@ GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef - panel2 + splitContainer1.Panel2 2 - - Fill + + splitContainer1.Panel2 - - 0, 0 + + System.Windows.Forms.SplitterPanel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 4, 4, 4, 4 + + splitContainer1 - - 585, 429 - - - 67 - - - False - - - zg1 - - - ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60 - - - panel2 - - - 3 - - - Fill - - - 0, 0 - - - 0, 0, 0, 0 - - - 585, 429 - - + 1 - - panel2 + + 577, 420 - - System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + 210 - + + 76 + + + splitContainer1 + + + System.Windows.Forms.SplitContainer, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + tableMap - + + 0 + + + Bottom, Left + + + NoControl + + + 10, 11 + + + 84, 13 + + + 13 + + + 0 + + + TXT_lat + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 0 + + + Bottom, Left + + + 438, 8 + + + 76, 20 + + + 69 + + + Change Zoom Level + + + Zoomlevel + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 1 + + + Bottom, Left + + + NoControl + + + 401, 11 + + + 34, 13 + + + 70 + + + Zoom + + + label1 + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 2 + + + Bottom, Left + + + NoControl + + + 100, 11 + + + 84, 13 + + + 14 + + + 0 + + + TXT_long + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 3 + + + Bottom, Left + + + NoControl + + + 190, 11 + + + 64, 13 + + + 15 + + + 0 + + + TXT_alt + + + ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + panel1 + + + 4 + + + Bottom, Left + + + True + + + NoControl + + + 325, 11 + + + 70, 17 + + + 68 + + + Auto Pan + + + Makes the map autopan based on current location + + + CHK_autopan + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 5 + + + Bottom, Left + + + True + + + NoControl + + + 260, 10 + + + 59, 17 + + + 62 + + + Tuning + + + Show the tunning graph, chowing target attitudes vs actual + + + CB_tuning + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + panel1 + + + 6 + + + Fill + + + 1, 428 + + + 0, 0, 0, 0 + + + 583, 30 + + + 0 + + + panel1 + + + System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tableMap + + 1 @@ -1649,7 +1679,7 @@ 0 - <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel2" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30" /></TableLayoutSettings> + <?xml version="1.0" encoding="utf-16"?><TableLayoutSettings><Controls><Control Name="splitContainer1" Row="0" RowSpan="1" Column="0" ColumnSpan="1" /><Control Name="panel1" Row="1" RowSpan="1" Column="0" ColumnSpan="1" /></Controls><Columns Styles="Percent,100" /><Rows Styles="Percent,100,Absolute,30,Absolute,20" /></TableLayoutSettings> MainH.Panel2 diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/JoystickSetup.resx b/Tools/ArdupilotMegaPlanner/bin/Release/JoystickSetup.resx index eccf946e39..9b38147048 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/JoystickSetup.resx +++ b/Tools/ArdupilotMegaPlanner/bin/Release/JoystickSetup.resx @@ -138,7 +138,7 @@ $this - 32 + 56 RZ @@ -171,7 +171,7 @@ $this - 31 + 55 RZ @@ -204,7 +204,7 @@ $this - 30 + 54 RZ @@ -237,7 +237,7 @@ $this - 29 + 53 RZ @@ -270,7 +270,7 @@ $this - 28 + 52 307, 70 @@ -294,7 +294,7 @@ $this - 23 + 47 307, 97 @@ -318,7 +318,7 @@ $this - 22 + 46 False @@ -345,7 +345,7 @@ $this - 21 + 45 307, 151 @@ -369,7 +369,7 @@ $this - 20 + 44 True @@ -400,7 +400,7 @@ $this - 19 + 43 True @@ -430,7 +430,7 @@ $this - 18 + 42 True @@ -460,7 +460,7 @@ $this - 17 + 41 True @@ -490,7 +490,7 @@ $this - 16 + 40 True @@ -517,7 +517,7 @@ $this - 15 + 39 True @@ -544,7 +544,7 @@ $this - 14 + 38 True @@ -571,7 +571,7 @@ $this - 13 + 37 True @@ -598,7 +598,7 @@ $this - 12 + 36 True @@ -628,7 +628,7 @@ $this - 9 + 33 True @@ -658,7 +658,7 @@ $this - 8 + 32 True @@ -688,7 +688,7 @@ $this - 7 + 31 True @@ -718,7 +718,7 @@ $this - 6 + 30 True @@ -748,11 +748,548 @@ $this - 5 + 29 17, 17 + + True + + + NoControl + + + 434, 81 + + + 64, 17 + + + 32 + + + Elevons + + + CHK_elevons + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 24 + + + True + + + NoControl + + + 413, 179 + + + 15, 14 + + + 37 + + + revCH5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 19 + + + True + + + NoControl + + + 9, 181 + + + 31, 13 + + + 36 + + + CH 5 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 20 + + + 307, 180 + + + 100, 13 + + + 35 + + + 0 + + + expo_ch5 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 21 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 176 + + + 70, 21 + + + 33 + + + CMB_CH5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 23 + + + True + + + NoControl + + + 413, 208 + + + 15, 14 + + + 43 + + + revCH6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 13 + + + True + + + NoControl + + + 9, 210 + + + 31, 13 + + + 42 + + + CH 6 + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 14 + + + 307, 209 + + + 100, 13 + + + 41 + + + 0 + + + expo_ch6 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 15 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 205 + + + 70, 21 + + + 39 + + + CMB_CH6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 17 + + + True + + + NoControl + + + 413, 237 + + + 15, 14 + + + 49 + + + revCH7 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 7 + + + True + + + NoControl + + + 9, 239 + + + 31, 13 + + + 48 + + + CH 7 + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 8 + + + 307, 238 + + + 100, 13 + + + 47 + + + 0 + + + expo_ch7 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 9 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 234 + + + 70, 21 + + + 45 + + + CMB_CH7 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 11 + + + True + + + NoControl + + + 413, 266 + + + 15, 14 + + + 55 + + + revCH8 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 1 + + + True + + + NoControl + + + 9, 268 + + + 31, 13 + + + 54 + + + CH 8 + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 2 + + + 307, 267 + + + 100, 13 + + + 53 + + + 0 + + + expo_ch8 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 3 + + + RZ + + + X + + + Y + + + SL1 + + + 72, 263 + + + 70, 21 + + + 51 + + + CMB_CH8 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 5 + + + NoControl + + + 148, 263 + + + 45, 23 + + + 56 + + + Auto Detect + + + BUT_detch8 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 0 + + + NoControl + + + 199, 262 + + + 100, 23 + + + 52 + + + horizontalProgressBar4 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 4 + NoControl @@ -778,7 +1315,7 @@ $this - 1 + 25 NoControl @@ -805,7 +1342,7 @@ $this - 2 + 26 NoControl @@ -832,7 +1369,7 @@ $this - 3 + 27 NoControl @@ -859,7 +1396,7 @@ $this - 4 + 28 NoControl @@ -886,7 +1423,7 @@ $this - 10 + 34 NoControl @@ -913,7 +1450,7 @@ $this - 11 + 35 NoControl @@ -937,7 +1474,7 @@ $this - 24 + 48 NoControl @@ -961,7 +1498,7 @@ $this - 25 + 49 NoControl @@ -985,7 +1522,7 @@ $this - 26 + 50 NoControl @@ -1009,34 +1546,160 @@ $this - 27 + 51 - - True + + NoControl - - 434, 81 + + 148, 176 - - 64, 17 + + 45, 23 - - 32 + + 38 - - Elevons + + Auto Detect - - CHK_elevons + + BUT_detch5 - - System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c - + $this - - 0 + + 18 + + + NoControl + + + 199, 175 + + + 100, 23 + + + 34 + + + horizontalProgressBar1 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 22 + + + NoControl + + + 148, 205 + + + 45, 23 + + + 44 + + + Auto Detect + + + BUT_detch6 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 12 + + + NoControl + + + 199, 204 + + + 100, 23 + + + 40 + + + horizontalProgressBar2 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 16 + + + NoControl + + + 148, 234 + + + 45, 23 + + + 50 + + + Auto Detect + + + BUT_detch7 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 6 + + + NoControl + + + 199, 233 + + + 100, 23 + + + 46 + + + horizontalProgressBar3 + + + ArdupilotMega.HorizontalProgressBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c + + + $this + + + 10 True @@ -1045,7 +1708,7 @@ 6, 13 - 498, 220 + 498, 331 diff --git a/apo/ControllerPlane.h b/apo/ControllerPlane.h index 408cb04491..368a323020 100644 --- a/apo/ControllerPlane.h +++ b/apo/ControllerPlane.h @@ -13,203 +13,146 @@ namespace apo { class ControllerPlane: public AP_Controller { -private: - AP_Var_group _group; - AP_Var_group _trimGroup; - AP_Uint8 _mode; - AP_Uint8 _rdrAilMix; - bool _needsTrim; - AP_Float _ailTrim; - AP_Float _elvTrim; - AP_Float _rdrTrim; - AP_Float _thrTrim; - enum { - ch_mode = 0, ch_roll, ch_pitch, ch_thr, ch_yaw - }; - enum { - k_chMode = k_radioChannelsStart, - k_chRoll, - k_chPitch, - k_chYaw, - k_chThr, - - k_pidBnkRll = k_controllersStart, - k_pidSpdPit, - k_pidPitPit, - k_pidYwrYaw, - k_pidHdgBnk, - k_pidAltThr, - - k_trim = k_customStart - }; - BlockPID pidBnkRll; // bank error to roll servo deflection - BlockPID pidSpdPit; // speed error to pitch command - BlockPID pidPitPit; // pitch error to pitch servo deflection - BlockPID pidYwrYaw; // yaw rate error to yaw servo deflection - BlockPID pidHdgBnk; // heading error to bank command - BlockPID pidAltThr; // altitude error to throttle deflection - bool requireRadio; - public: - ControllerPlane(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal), - _group(k_cntrl, PSTR("cntrl_")), - _trimGroup(k_trim, PSTR("trim_")), - _mode(&_group, 1, MAV_MODE_UNINIT, PSTR("mode")), - _rdrAilMix(&_group, 2, rdrAilMix, PSTR("rdrAilMix")), - _needsTrim(false), - _ailTrim(&_trimGroup, 1, ailTrim, PSTR("ail")), - _elvTrim(&_trimGroup, 2, elvTrim, PSTR("elv")), - _rdrTrim(&_trimGroup, 3, rdrTrim, PSTR("rdr")), - _thrTrim(&_trimGroup, 4, thrTrim, PSTR("thr")), - pidBnkRll(new AP_Var_group(k_pidBnkRll, PSTR("bnkRll_")), 1, - pidBnkRllP, pidBnkRllI, pidBnkRllD, pidBnkRllAwu, - pidBnkRllLim, pidBnkRllDFCut), - pidPitPit(new AP_Var_group(k_pidPitPit, PSTR("pitPit_")), 1, - pidPitPitP, pidPitPitI, pidPitPitD, pidPitPitAwu, - pidPitPitLim, pidPitPitDFCut), - pidSpdPit(new AP_Var_group(k_pidSpdPit, PSTR("spdPit_")), 1, - pidSpdPitP, pidSpdPitI, pidSpdPitD, pidSpdPitAwu, - pidSpdPitLim, pidSpdPitDFCut), - pidYwrYaw(new AP_Var_group(k_pidYwrYaw, PSTR("ywrYaw_")), 1, - pidYwrYawP, pidYwrYawI, pidYwrYawD, pidYwrYawAwu, - pidYwrYawLim, pidYwrYawDFCut), - pidHdgBnk(new AP_Var_group(k_pidHdgBnk, PSTR("hdgBnk_")), 1, - pidHdgBnkP, pidHdgBnkI, pidHdgBnkD, pidHdgBnkAwu, - pidHdgBnkLim, pidHdgBnkDFCut), - pidAltThr(new AP_Var_group(k_pidAltThr, PSTR("altThr_")), 1, - pidAltThrP, pidAltThrI, pidAltThrD, pidAltThrAwu, - pidAltThrLim, pidAltThrDFCut), - requireRadio(false) { + ControllerPlane(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_yaw,0.1,-0.9,0.9),ch_mode), + _trimGroup(k_trim, PSTR("trim_")), + _rdrAilMix(&_group, 2, rdrAilMix, PSTR("rdrAilMix")), + _needsTrim(false), + _ailTrim(&_trimGroup, 1, ailTrim, PSTR("ail")), + _elvTrim(&_trimGroup, 2, elvTrim, PSTR("elv")), + _rdrTrim(&_trimGroup, 3, rdrTrim, PSTR("rdr")), + _thrTrim(&_trimGroup, 4, thrTrim, PSTR("thr")), + pidBnkRll(new AP_Var_group(k_pidBnkRll, PSTR("bnkRll_")), 1, + pidBnkRllP, pidBnkRllI, pidBnkRllD, pidBnkRllAwu, + pidBnkRllLim, pidBnkRllDFCut), + pidPitPit(new AP_Var_group(k_pidPitPit, PSTR("pitPit_")), 1, + pidPitPitP, pidPitPitI, pidPitPitD, pidPitPitAwu, + pidPitPitLim, pidPitPitDFCut), + pidSpdPit(new AP_Var_group(k_pidSpdPit, PSTR("spdPit_")), 1, + pidSpdPitP, pidSpdPitI, pidSpdPitD, pidSpdPitAwu, + pidSpdPitLim, pidSpdPitDFCut), + pidYwrYaw(new AP_Var_group(k_pidYwrYaw, PSTR("ywrYaw_")), 1, + pidYwrYawP, pidYwrYawI, pidYwrYawD, pidYwrYawAwu, + pidYwrYawLim, pidYwrYawDFCut), + pidHdgBnk(new AP_Var_group(k_pidHdgBnk, PSTR("hdgBnk_")), 1, + pidHdgBnkP, pidHdgBnkI, pidHdgBnkD, pidHdgBnkAwu, + pidHdgBnkLim, pidHdgBnkDFCut), + pidAltThr(new AP_Var_group(k_pidAltThr, PSTR("altThr_")), 1, + pidAltThrP, pidAltThrI, pidAltThrD, pidAltThrAwu, + pidAltThrLim, pidAltThrDFCut), + requireRadio(false), _aileron(0), _elevator(0), _rudder(0), _throttle(0) { - _hal->debug->println_P(PSTR("initializing plane controller")); + _hal->debug->println_P(PSTR("initializing plane controller")); - _hal->rc.push_back( - new AP_RcChannel(k_chMode, PSTR("mode_"), APM_RC, 5, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chRoll, PSTR("roll_"), APM_RC, 0, 1200, - 1500, 1800, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chPitch, PSTR("pitch_"), APM_RC, 1, 1200, - 1500, 1800, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chThr, PSTR("thr_"), APM_RC, 2, 1100, 1100, - 1900, RC_MODE_INOUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chYaw, PSTR("yaw_"), APM_RC, 3, 1200, 1500, - 1800, RC_MODE_INOUT, false)); - } - virtual MAV_MODE getMode() { - return (MAV_MODE) _mode.get(); - } - virtual void update(const float & dt) { + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("mode_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRoll, PSTR("roll_"), APM_RC, 0, 1200, + 1500, 1800, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chPitch, PSTR("pitch_"), APM_RC, 1, 1200, + 1500, 1800, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("thr_"), APM_RC, 2, 1100, 1100, + 1900, RC_MODE_INOUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chYaw, PSTR("yaw_"), APM_RC, 3, 1200, 1500, + 1800, RC_MODE_INOUT, false)); + } - // check for heartbeat - if (_hal->heartBeatLost()) { - _mode = MAV_MODE_FAILSAFE; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("comm lost, send heartbeat from gcs\n")); - return; - // if the value of the throttle is less than 5% cut motor power - } else if (requireRadio && _hal->rc[ch_thr]->getRadioPosition() < 0.05) { - _mode = MAV_MODE_LOCKED; - setAllRadioChannelsToNeutral(); - _hal->setState(MAV_STATE_STANDBY); - return; - // if in live mode then set state to active - } else if (_hal->getMode() == MODE_LIVE) { - _hal->setState(MAV_STATE_ACTIVE); - // if in hardware in the loop (control) mode, set to hilsim - } else if (_hal->getMode() == MODE_HIL_CNTL) { - _hal->setState(MAV_STATE_HILSIM); - } +private: + // methdos + void manualLoop(const float dt) { + setAllRadioChannelsManually(); + // force auto to read new manual trim + if (_needsTrim == false) + _needsTrim = true; + } + void autoLoop(const float dt) { + _aileron = pidBnkRll.update( + pidHdgBnk.update(_guide->getHeadingError(), dt) - _nav->getRoll(), dt); + _elevator = pidPitPit.update( + -pidSpdPit.update( + _guide->getAirSpeedCommand() - _nav->getAirSpeed(), + dt) - _nav->getPitch(), dt); + _rudder = pidYwrYaw.update(-_nav->getYawRate(), dt); - // read switch to set mode - if (_hal->rc[ch_mode]->getRadioPosition() > 0) { - _mode = MAV_MODE_MANUAL; - } else { - _mode = MAV_MODE_AUTO; - } + // desired yaw rate is zero, needs washout + _throttle = pidAltThr.update( + _guide->getAltitudeCommand() - _nav->getAlt(), dt); - // manual mode - switch (_mode) { + if (_needsTrim) { + // need to subtract current controller deflections so control + // surfaces are actually at the same position as manual flight + _ailTrim = _hal->rc[ch_roll]->getRadioPosition() - _aileron; + _elvTrim = _hal->rc[ch_pitch]->getRadioPosition() - _elevator; + _rdrTrim = _hal->rc[ch_yaw]->getRadioPosition() - _rudder; + _thrTrim = _hal->rc[ch_thrust]->getRadioPosition() - _throttle; + _needsTrim = false; + } - case MAV_MODE_MANUAL: { - setAllRadioChannelsManually(); + // actuator mixing/ output + _aileron += _rdrAilMix * _rudder + _ailTrim; + _elevator += _elvTrim; + _rudder += _rdrTrim; + _throttle += _thrTrim; + } + void setMotorsActive() { + // turn all motors off if below 0.1 throttle + if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) { + setAllRadioChannelsToNeutral(); + } else { + _hal->rc[ch_roll]->setPosition(_aileron); + _hal->rc[ch_yaw]->setPosition(_rudder); + _hal->rc[ch_pitch]->setPosition(_elevator); + _hal->rc[ch_thrust]->setPosition(_throttle); + } + } - // force auto to read new manual trim - if (_needsTrim == false) - _needsTrim = true; - //_hal->debug->println("manual"); - break; - } - case MAV_MODE_AUTO: { - float headingError = _guide->getHeadingCommand() - - _nav->getYaw(); - if (headingError > 180 * deg2Rad) - headingError -= 360 * deg2Rad; - if (headingError < -180 * deg2Rad) - headingError += 360 * deg2Rad; + // attributes + enum { + ch_mode = 0, ch_roll, ch_pitch, ch_thrust, ch_yaw + }; + enum { + k_chMode = k_radioChannelsStart, + k_chRoll, + k_chPitch, + k_chYaw, + k_chThr, - float aileron = pidBnkRll.update( - pidHdgBnk.update(headingError, dt) - _nav->getRoll(), dt); - float elevator = pidPitPit.update( - -pidSpdPit.update( - _guide->getAirSpeedCommand() - _nav->getAirSpeed(), - dt) - _nav->getPitch(), dt); - float rudder = pidYwrYaw.update(-_nav->getYawRate(), dt); - // desired yaw rate is zero, needs washout - float throttle = pidAltThr.update( - _guide->getAltitudeCommand() - _nav->getAlt(), dt); + k_pidBnkRll = k_controllersStart, + k_pidSpdPit, + k_pidPitPit, + k_pidYwrYaw, + k_pidHdgBnk, + k_pidAltThr, - // if needs trim - if (_needsTrim) { - // need to subtract current controller deflections so control - // surfaces are actually at the same position as manual flight - _ailTrim = _hal->rc[ch_roll]->getRadioPosition() - aileron; - _elvTrim = _hal->rc[ch_pitch]->getRadioPosition() - elevator; - _rdrTrim = _hal->rc[ch_yaw]->getRadioPosition() - rudder; - _thrTrim = _hal->rc[ch_thr]->getRadioPosition() - throttle; - _needsTrim = false; - } - - // actuator mixing/ output - _hal->rc[ch_roll]->setPosition( - aileron + _rdrAilMix * rudder + _ailTrim); - _hal->rc[ch_yaw]->setPosition(rudder + _rdrTrim); - _hal->rc[ch_pitch]->setPosition(elevator + _elvTrim); - _hal->rc[ch_thr]->setPosition(throttle + _thrTrim); - - //_hal->debug->println("automode"); - - - // heading debug -// Serial.print("heading command: "); Serial.println(_guide->getHeadingCommand()); -// Serial.print("heading: "); Serial.println(_nav->getYaw()); -// Serial.print("heading error: "); Serial.println(headingError); - - // alt debug -// Serial.print("alt command: "); Serial.println(_guide->getAltitudeCommand()); -// Serial.print("alt: "); Serial.println(_nav->getAlt()); -// Serial.print("alt error: "); Serial.println(_guide->getAltitudeCommand() - _nav->getAlt()); - break; - } - - default: { - setAllRadioChannelsToNeutral(); - _mode = MAV_MODE_FAILSAFE; - _hal->setState(MAV_STATE_EMERGENCY); - _hal->debug->printf_P(PSTR("unknown controller mode\n")); - break; - } - - } - } + k_trim = k_customStart + }; + AP_Var_group _trimGroup; + AP_Uint8 _rdrAilMix; + bool _needsTrim; + AP_Float _ailTrim; + AP_Float _elvTrim; + AP_Float _rdrTrim; + AP_Float _thrTrim; + BlockPID pidBnkRll; // bank error to roll servo deflection + BlockPID pidSpdPit; // speed error to pitch command + BlockPID pidPitPit; // pitch error to pitch servo deflection + BlockPID pidYwrYaw; // yaw rate error to yaw servo deflection + BlockPID pidHdgBnk; // heading error to bank command + BlockPID pidAltThr; // altitude error to throttle deflection + bool requireRadio; + float _aileron; + float _elevator; + float _rudder; + float _throttle; }; } // namespace apo #endif /* CONTROLLERPLANE_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/apo/ControllerQuad.h b/apo/ControllerQuad.h index 847f5617fd..920c878abe 100644 --- a/apo/ControllerQuad.h +++ b/apo/ControllerQuad.h @@ -10,310 +10,179 @@ #include "../APO/AP_Controller.h" #include "../APO/AP_BatteryMonitor.h" +#include "../APO/AP_ArmingMechanism.h" namespace apo { class ControllerQuad: public AP_Controller { public: + ControllerQuad(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal) : + AP_Controller(nav, guide, hal, new AP_ArmingMechanism(hal,ch_thrust,ch_yaw,0.1,-0.9,0.9), ch_mode), + pidRoll(new AP_Var_group(k_pidRoll, PSTR("ROLL_")), 1, + PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, + PID_ATT_LIM, PID_ATT_DFCUT), + pidPitch(new AP_Var_group(k_pidPitch, PSTR("PITCH_")), 1, + PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, + PID_ATT_LIM, PID_ATT_DFCUT), + pidYaw(new AP_Var_group(k_pidYaw, PSTR("YAW_")), 1, + PID_YAWPOS_P, PID_YAWPOS_I, PID_YAWPOS_D, + PID_YAWPOS_AWU, PID_YAWPOS_LIM, PID_ATT_DFCUT), + pidYawRate(new AP_Var_group(k_pidYawRate, PSTR("YAWRT_")), 1, + PID_YAWSPEED_P, PID_YAWSPEED_I, PID_YAWSPEED_D, + PID_YAWSPEED_AWU, PID_YAWSPEED_LIM, PID_YAWSPEED_DFCUT), + pidPN(new AP_Var_group(k_pidPN, PSTR("NORTH_")), 1, PID_POS_P, + PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT), + pidPE(new AP_Var_group(k_pidPE, PSTR("EAST_")), 1, PID_POS_P, + PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT), + pidPD(new AP_Var_group(k_pidPD, PSTR("DOWN_")), 1, PID_POS_Z_P, + PID_POS_Z_I, PID_POS_Z_D, PID_POS_Z_AWU, PID_POS_Z_LIM, PID_POS_DFCUT), + _thrustMix(0), _pitchMix(0), _rollMix(0), _yawMix(0), + _cmdRoll(0), _cmdPitch(0), _cmdYawRate(0) { + _hal->debug->println_P(PSTR("initializing quad controller")); - /** - * note that these are not the controller radio channel numbers, they are just - * unique keys so they can be reaccessed from the hal rc vector - */ - enum { - CH_MODE = 0, // note scicoslab channels set mode, left, right, front, back order - CH_RIGHT, - CH_LEFT, - CH_FRONT, - CH_BACK, - CH_ROLL, - CH_PITCH, - CH_THRUST, - CH_YAW - }; + /* + * allocate radio channels + * the order of the channels has to match the enumeration above + */ + _hal->rc.push_back( + new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 0, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 1, 1100, + 1100, 1900, RC_MODE_OUT, false)); - // must match channel enum - enum { - k_chMode = k_radioChannelsStart, - k_chRight, - k_chLeft, - k_chFront, - k_chBack, - k_chRoll, - k_chPitch, - k_chThr, - k_chYaw - }; - - enum { - k_pidGroundSpeed2Throttle = k_controllersStart, - k_pidStr, - k_pidPN, - k_pidPE, - k_pidPD, - k_pidRoll, - k_pidPitch, - k_pidYawRate, - k_pidYaw, - }; - - ControllerQuad(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - AP_Controller(nav, guide, hal), - pidRoll(new AP_Var_group(k_pidRoll, PSTR("ROLL_")), 1, - PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, - PID_ATT_LIM, PID_ATT_DFCUT), - pidPitch(new AP_Var_group(k_pidPitch, PSTR("PITCH_")), 1, - PID_ATT_P, PID_ATT_I, PID_ATT_D, PID_ATT_AWU, - PID_ATT_LIM, PID_ATT_DFCUT), - pidYaw(new AP_Var_group(k_pidYaw, PSTR("YAW_")), 1, - PID_YAWPOS_P, PID_YAWPOS_I, PID_YAWPOS_D, - PID_YAWPOS_AWU, PID_YAWPOS_LIM, PID_ATT_DFCUT), - pidYawRate(new AP_Var_group(k_pidYawRate, PSTR("YAWRT_")), 1, - PID_YAWSPEED_P, PID_YAWSPEED_I, PID_YAWSPEED_D, - PID_YAWSPEED_AWU, PID_YAWSPEED_LIM, PID_YAWSPEED_DFCUT), - pidPN(new AP_Var_group(k_pidPN, PSTR("NORTH_")), 1, PID_POS_P, - PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT), - pidPE(new AP_Var_group(k_pidPE, PSTR("EAST_")), 1, PID_POS_P, - PID_POS_I, PID_POS_D, PID_POS_AWU, PID_POS_LIM, PID_POS_DFCUT), - pidPD(new AP_Var_group(k_pidPD, PSTR("DOWN_")), 1, PID_POS_Z_P, - PID_POS_Z_I, PID_POS_Z_D, PID_POS_Z_AWU, PID_POS_Z_LIM, PID_POS_DFCUT), - _armingClock(0), _thrustMix(0), _pitchMix(0), _rollMix(0), _yawMix(0), - _cmdRoll(0), _cmdPitch(0), _cmdYawRate(0), _mode(MAV_MODE_LOCKED) { - /* - * allocate radio channels - * the order of the channels has to match the enumeration above - */ - _hal->rc.push_back( - new AP_RcChannel(k_chMode, PSTR("MODE_"), APM_RC, 5, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chRight, PSTR("RIGHT_"), APM_RC, 0, 1100, - 1100, 1900, RC_MODE_OUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chLeft, PSTR("LEFT_"), APM_RC, 1, 1100, - 1100, 1900, RC_MODE_OUT, false)); - - _hal->rc.push_back( - new AP_RcChannel(k_chFront, PSTR("FRONT_"), APM_RC, 2, 1100, - 1100, 1900, RC_MODE_OUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chBack, PSTR("BACK_"), APM_RC, 3, 1100, - 1100, 1900, RC_MODE_OUT, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chRoll, PSTR("ROLL_"), APM_RC, 0, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chPitch, PSTR("PITCH_"), APM_RC, 1, 1100, - 1500, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chThr, PSTR("THRUST_"), APM_RC, 2, 1100, - 1100, 1900, RC_MODE_IN, false)); - _hal->rc.push_back( - new AP_RcChannel(k_chYaw, PSTR("YAW_"), APM_RC, 3, 1100, 1500, - 1900, RC_MODE_IN, false)); - } - - virtual void update(const float & dt) { - //_hal->debug->printf_P(PSTR("thr: %f, yaw: %f\n"),_hal->rc[CH_THRUST]->getRadioPosition(),_hal->rc[CH_YAW]->getRadioPosition()); - - // arming - // - // to arm: put stick to bottom right for 100 controller cycles - // (max yaw, min throttle) - // - // didn't use clock here in case of millis() roll over - // for long runs - if ( (_hal->getState() != MAV_STATE_ACTIVE) & - (_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) && - (_hal->rc[CH_YAW]->getRadioPosition() < -0.9) ) { - - // always start clock at 0 - if (_armingClock<0) _armingClock = 0; - - if (_armingClock++ >= 100) { - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed")); - _hal->setState(MAV_STATE_ACTIVE); - } else { - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("arming")); - } - } - // disarming - // - // to disarm: put stick to bottom left for 100 controller cycles - // (min yaw, min throttle) - else if ( (_hal->getState() == MAV_STATE_ACTIVE) & - (_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) && - (_hal->rc[CH_YAW]->getRadioPosition() > 0.9) ) { - - // always start clock at 0 - if (_armingClock>0) _armingClock = 0; - - if (_armingClock-- <= -100) { - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed")); - _hal->setState(MAV_STATE_STANDBY); - } else { - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarming")); - } - } - // reset arming clock and report status - else if (_armingClock != 0) { - _armingClock = 0; - if (_hal->getState()==MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed")); - else if (_hal->getState()!=MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed")); - } - - // determine flight mode - // - // check for heartbeat from gcs, if not found go to failsafe - if (_hal->heartBeatLost()) { - _mode = MAV_MODE_FAILSAFE; - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("configure gcs to send heartbeat")); - // if battery less than 5%, go to failsafe - } else if (_hal->batteryMonitor->getPercentage() < 5) { - _mode = MAV_MODE_FAILSAFE; - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery")); - // manual/auto switch - } else { - // if all emergencies cleared, fall back to standby - if (_hal->getState()==MAV_STATE_EMERGENCY) _hal->setState(MAV_STATE_STANDBY); - if (_hal->rc[CH_MODE]->getRadioPosition() > 0) _mode = MAV_MODE_MANUAL; - else _mode = MAV_MODE_AUTO; - } - - // handle flight modes - switch(_mode) { - - case MAV_MODE_LOCKED: { - _hal->setState(MAV_STATE_STANDBY); - break; - } - - case MAV_MODE_FAILSAFE: { - _hal->setState(MAV_STATE_EMERGENCY); - break; - } - - case MAV_MODE_MANUAL: { - manualPositionLoop(); - autoAttitudeLoop(dt); - break; - } - - case MAV_MODE_AUTO: { - // until position loop is tested just - // go to standby - _hal->setState(MAV_STATE_STANDBY); - - //attitudeLoop(); - // XXX autoPositionLoop NOT TESTED, don't uncomment yet - //autoPositionLoop(dt); - //autoAttitudeLoop(dt); - break; - } - - default: { - _hal->gcs->sendText(SEVERITY_HIGH, PSTR("unknown mode")); - _hal->setState(MAV_STATE_EMERGENCY); - } - } - - // this sends commands to motors - setMotors(); - } - - virtual MAV_MODE getMode() { - return (MAV_MODE) _mode.get(); - } + _hal->rc.push_back( + new AP_RcChannel(k_chFront, PSTR("FRONT_"), APM_RC, 2, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chBack, PSTR("BACK_"), APM_RC, 3, 1100, + 1100, 1900, RC_MODE_OUT, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chRoll, PSTR("ROLL_"), APM_RC, 0, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chPitch, PSTR("PITCH_"), APM_RC, 1, 1100, + 1500, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chThr, PSTR("THRUST_"), APM_RC, 2, 1100, + 1100, 1900, RC_MODE_IN, false)); + _hal->rc.push_back( + new AP_RcChannel(k_chYaw, PSTR("YAW_"), APM_RC, 3, 1100, 1500, + 1900, RC_MODE_IN, false)); + } private: + // methods + void manualLoop(const float dt) { + setAllRadioChannelsManually(); + _cmdRoll = -0.5 * _hal->rc[ch_roll]->getPosition(); + _cmdPitch = -0.5 * _hal->rc[ch_pitch]->getPosition(); + _cmdYawRate = -1 * _hal->rc[ch_yaw]->getPosition(); + _thrustMix = _hal->rc[ch_thrust]->getPosition(); + autoAttitudeLoop(dt); + } + void autoLoop(const float dt) { + autoPositionLoop(dt); + autoAttitudeLoop(dt); - AP_Uint8 _mode; - BlockPIDDfb pidRoll, pidPitch, pidYaw; - BlockPID pidYawRate; - BlockPIDDfb pidPN, pidPE, pidPD; - int32_t _armingClock; + // XXX currently auto loop not tested, so + // put vehicle in standby + _hal->setState(MAV_STATE_STANDBY); + } + void autoPositionLoop(float dt) { + float cmdNorthTilt = pidPN.update(_nav->getPN(),_nav->getVN(),dt); + float cmdEastTilt = pidPE.update(_nav->getPE(),_nav->getVE(),dt); + float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt); - float _thrustMix, _pitchMix, _rollMix, _yawMix; - float _cmdRoll, _cmdPitch, _cmdYawRate; + // "transform-to-body" + { + float trigSin = sin(-_nav->getYaw()); + float trigCos = cos(-_nav->getYaw()); + _cmdPitch = cmdEastTilt * trigCos - cmdNorthTilt * trigSin; + _cmdRoll = -cmdEastTilt * trigSin + cmdNorthTilt * trigCos; + // note that the north tilt is negative of the pitch + } + _cmdYawRate = 0; - void manualPositionLoop() { - setAllRadioChannelsManually(); - _cmdRoll = -0.5 * _hal->rc[CH_ROLL]->getPosition(); - _cmdPitch = -0.5 * _hal->rc[CH_PITCH]->getPosition(); - _cmdYawRate = -1 * _hal->rc[CH_YAW]->getPosition(); - _thrustMix = _hal->rc[CH_THRUST]->getPosition(); - } + _thrustMix = THRUST_HOVER_OFFSET + cmdDown; - void autoPositionLoop(float dt) { - float cmdNorthTilt = pidPN.update(_nav->getPN(),_nav->getVN(),dt); - float cmdEastTilt = pidPE.update(_nav->getPE(),_nav->getVE(),dt); - float cmdDown = pidPD.update(_nav->getPD(),_nav->getVD(),dt); + // "thrust-trim-adjust" + if (fabs(_cmdRoll) > 0.5) _thrustMix *= 1.13949393; + else _thrustMix /= cos(_cmdRoll); - // "transform-to-body" - { - float trigSin = sin(-_nav->getYaw()); - float trigCos = cos(-_nav->getYaw()); - _cmdPitch = cmdEastTilt * trigCos - cmdNorthTilt * trigSin; - _cmdRoll = -cmdEastTilt * trigSin + cmdNorthTilt * trigCos; - // note that the north tilt is negative of the pitch - } - _cmdYawRate = 0; + if (fabs(_cmdPitch) > 0.5) _thrustMix *= 1.13949393; + else _thrustMix /= cos(_cmdPitch); + } + void autoAttitudeLoop(float dt) { + _rollMix = pidRoll.update(_cmdRoll - _nav->getRoll(), + _nav->getRollRate(), dt); + _pitchMix = pidPitch.update(_cmdPitch - _nav->getPitch(), + _nav->getPitchRate(), dt); + _yawMix = pidYawRate.update(_cmdYawRate - _nav->getYawRate(), dt); + } + void setMotorsActive() { + // turn all motors off if below 0.1 throttle + if (fabs(_hal->rc[ch_thrust]->getRadioPosition()) < 0.1) { + setAllRadioChannelsToNeutral(); + } else { + _hal->rc[ch_right]->setPosition(_thrustMix - _rollMix + _yawMix); + _hal->rc[ch_left]->setPosition(_thrustMix + _rollMix + _yawMix); + _hal->rc[ch_front]->setPosition(_thrustMix + _pitchMix - _yawMix); + _hal->rc[ch_back]->setPosition(_thrustMix - _pitchMix - _yawMix); + } + } - _thrustMix = THRUST_HOVER_OFFSET + cmdDown; - - // "thrust-trim-adjust" - if (fabs(_cmdRoll) > 0.5) _thrustMix *= 1.13949393; - else _thrustMix /= cos(_cmdRoll); - - if (fabs(_cmdPitch) > 0.5) _thrustMix *= 1.13949393; - else _thrustMix /= cos(_cmdPitch); - } - - void autoAttitudeLoop(float dt) { - _rollMix = pidRoll.update(_cmdRoll - _nav->getRoll(), - _nav->getRollRate(), dt); - _pitchMix = pidPitch.update(_cmdPitch - _nav->getPitch(), - _nav->getPitchRate(), dt); - _yawMix = pidYawRate.update(_cmdYawRate - _nav->getYawRate(), dt); - } - - void setMotors() { - - switch (_hal->getState()) { - - case MAV_STATE_ACTIVE: { - digitalWrite(_hal->aLedPin, HIGH); - // turn all motors off if below 0.1 throttle - if (_hal->rc[CH_THRUST]->getRadioPosition() < 0.1) { - setAllRadioChannelsToNeutral(); - } else { - _hal->rc[CH_RIGHT]->setPosition(_thrustMix - _rollMix + _yawMix); - _hal->rc[CH_LEFT]->setPosition(_thrustMix + _rollMix + _yawMix); - _hal->rc[CH_FRONT]->setPosition(_thrustMix + _pitchMix - _yawMix); - _hal->rc[CH_BACK]->setPosition(_thrustMix - _pitchMix - _yawMix); - } - break; - } - case MAV_STATE_EMERGENCY: { - digitalWrite(_hal->aLedPin, LOW); - setAllRadioChannelsToNeutral(); - break; - } - case MAV_STATE_STANDBY: { - digitalWrite(_hal->aLedPin,LOW); - setAllRadioChannelsToNeutral(); - break; - } - default: { - digitalWrite(_hal->aLedPin, LOW); - setAllRadioChannelsToNeutral(); - } - - } - } + // attributes + /** + * note that these are not the controller radio channel numbers, they are just + * unique keys so they can be reaccessed from the hal rc vector + */ + enum { + ch_mode = 0, // note scicoslab channels set mode, left, right, front, back order + ch_right, + ch_left, + ch_front, + ch_back, + ch_roll, + ch_pitch, + ch_thrust, + ch_yaw + }; + // must match channel enum + enum { + k_chMode = k_radioChannelsStart, + k_chRight, + k_chLeft, + k_chFront, + k_chBack, + k_chRoll, + k_chPitch, + k_chThr, + k_chYaw + }; + enum { + k_pidGroundSpeed2Throttle = k_controllersStart, + k_pidStr, + k_pidPN, + k_pidPE, + k_pidPD, + k_pidRoll, + k_pidPitch, + k_pidYawRate, + k_pidYaw, + }; + BlockPIDDfb pidRoll, pidPitch, pidYaw; + BlockPID pidYawRate; + BlockPIDDfb pidPN, pidPE, pidPD; + float _thrustMix, _pitchMix, _rollMix, _yawMix; + float _cmdRoll, _cmdPitch, _cmdYawRate; }; } // namespace apo #endif /* CONTROLLERQUAD_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/apo/PlaneEasystar.h b/apo/PlaneEasystar.h index 87649f48a3..54e331f84d 100644 --- a/apo/PlaneEasystar.h +++ b/apo/PlaneEasystar.h @@ -11,7 +11,7 @@ // vehicle options static const apo::vehicle_t vehicle = apo::VEHICLE_PLANE; static const apo::halMode_t halMode = apo::MODE_LIVE; -static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_2560; +static const apo::board_t board = apo::BOARD_ARDUPILOTMEGA_1280; static const uint8_t heartBeatTimeout = 3; // algorithm selection @@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3; #define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL // baud rates -static uint32_t debugBaud = 57600; -static uint32_t telemBaud = 57600; -static uint32_t gpsBaud = 38400; -static uint32_t hilBaud = 57600; +static const uint32_t debugBaud = 57600; +static const uint32_t telemBaud = 57600; +static const uint32_t gpsBaud = 38400; +static const uint32_t hilBaud = 57600; // optional sensors static const bool gpsEnabled = false; @@ -40,7 +40,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD // compass orientation: See AP_Compass_HMC5843.h for possible values // battery monitoring -static const bool batteryMonitorEnabled = true; +static const bool batteryMonitorEnabled = false; static const uint8_t batteryPin = 0; static const float batteryVoltageDivRatio = 6; static const float batteryMinVolt = 10.0; @@ -117,6 +117,12 @@ static const float elvTrim = 0.0; static const float rdrTrim = 0.0; static const float thrTrim = 0.5; +// guidance +static const float velCmd = 1; // m/s +static const float xt = 10; // cross track gain +static const float xtLim = 90; // cross track angle limit, deg + #include "ControllerPlane.h" #endif /* PLANEEASYSTAR_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/apo/QuadArducopter.h b/apo/QuadArducopter.h index e741deab7b..670aa18e05 100644 --- a/apo/QuadArducopter.h +++ b/apo/QuadArducopter.h @@ -27,10 +27,10 @@ static const uint8_t heartBeatTimeout = 3; #define RANGE_FINDER_CLASS AP_RangeFinder_MaxsonarXL // baud rates -static uint32_t debugBaud = 57600; -static uint32_t telemBaud = 57600; -static uint32_t gpsBaud = 38400; -static uint32_t hilBaud = 57600; +static const uint32_t debugBaud = 57600; +static const uint32_t telemBaud = 57600; +static const uint32_t gpsBaud = 38400; +static const uint32_t hilBaud = 57600; // optional sensors static const bool gpsEnabled = false; @@ -54,7 +54,7 @@ static const bool rangeFinderUpEnabled = false; static const bool rangeFinderDownEnabled = false; // loop rates -static const float loopRate = 400; // attitude nav +static const float loopRate = 250; // attitude nav static const float loop0Rate = 50; // controller static const float loop1Rate = 10; // pos nav/ gcs fast static const float loop2Rate = 1; // gcs slow @@ -91,9 +91,14 @@ static const float PID_YAWSPEED_D = 0; static const float PID_YAWSPEED_LIM = .05; // 5 % motors static const float PID_YAWSPEED_AWU = 0.0; static const float PID_YAWSPEED_DFCUT = 3.0; // 3 Radians, about 1 Hz - static const float THRUST_HOVER_OFFSET = 0.475; +// guidance +static const float velCmd = 1; // m/s +static const float xt = 10; // cross track gain +static const float xtLim = 90; // cross track angle limit, deg + #include "ControllerQuad.h" #endif /* QUADARDUCOPTER_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/apo/apo.pde b/apo/apo.pde index a413f824e3..cdd4455bfd 100644 --- a/apo/apo.pde +++ b/apo/apo.pde @@ -17,8 +17,8 @@ #include // Vehicle Configuration -#include "QuadArducopter.h" -//#include "PlaneEasystar.h" +//#include "QuadArducopter.h" +#include "PlaneEasystar.h" // ArduPilotOne Default Setup #include "APO_DefaultSetup.h" diff --git a/libraries/APM_BMP085/APM_BMP085.h b/libraries/APM_BMP085/APM_BMP085.h index 7b75c7c865..fb44e68a8c 100644 --- a/libraries/APM_BMP085/APM_BMP085.h +++ b/libraries/APM_BMP085/APM_BMP085.h @@ -4,7 +4,7 @@ #define TEMP_FILTER_SIZE 16 #define PRESS_FILTER_SIZE 10 -#include +#include "APM_BMP085_hil.h" class APM_BMP085_Class { diff --git a/libraries/APO/APO.h b/libraries/APO/APO.h index 357591c7e2..360b93dada 100644 --- a/libraries/APO/APO.h +++ b/libraries/APO/APO.h @@ -16,6 +16,10 @@ #include "AP_Navigator.h" #include "AP_RcChannel.h" #include "AP_BatteryMonitor.h" -//#include "AP_Var_keys.h" +#include "AP_ArmingMechanism.h" +#include "AP_CommLink.h" +#include "AP_Var_keys.h" +#include "constants.h" #endif /* APO_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/APO_DefaultSetup.h b/libraries/APO/APO_DefaultSetup.h index cbdd2c6688..82ee0250b8 100644 --- a/libraries/APO/APO_DefaultSetup.h +++ b/libraries/APO/APO_DefaultSetup.h @@ -14,168 +14,171 @@ static apo::AP_Autopilot * autoPilot; void setup() { - using namespace apo; - - AP_Var::load_all(); + using namespace apo; - // Declare all parts of the system - AP_Navigator * navigator = NULL; - AP_Guide * guide = NULL; - AP_Controller * controller = NULL; - AP_HardwareAbstractionLayer * hal = NULL; + AP_Var::load_all(); - /* - * Communications - */ - Serial.begin(debugBaud, 128, 128); // debug - - // hardware abstraction layer - hal = new AP_HardwareAbstractionLayer( - halMode, board, vehicle, heartBeatTimeout); - - // debug serial - hal->debug = &Serial; - hal->debug->println_P(PSTR("initializing debug line")); + // Declare all parts of the system + AP_Navigator * navigator = NULL; + AP_Guide * guide = NULL; + AP_Controller * controller = NULL; + AP_HardwareAbstractionLayer * hal = NULL; - /* - * Sensor initialization - */ - if (hal->getMode() == MODE_LIVE) { + /* + * Communications + */ + Serial.begin(debugBaud, 128, 128); // debug - hal->debug->println_P(PSTR("initializing adc")); - hal->adc = new ADC_CLASS; - hal->adc->Init(); + // hardware abstraction layer + hal = new AP_HardwareAbstractionLayer( + halMode, board, vehicle, heartBeatTimeout); - if (batteryMonitorEnabled) { - hal->batteryMonitor = new AP_BatteryMonitor(batteryPin,batteryVoltageDivRatio,batteryMinVolt,batteryMaxVolt); - } + // debug serial + hal->debug = &Serial; + hal->debug->println_P(PSTR("initializing debug line")); - if (gpsEnabled) { - Serial1.begin(gpsBaud, 128, 16); // gps - hal->debug->println_P(PSTR("initializing gps")); - AP_GPS_Auto gpsDriver(&Serial1, &(hal->gps)); - hal->gps = &gpsDriver; - hal->gps->callback = delay; - hal->gps->init(); - } + /* + * Sensor initialization + */ + if (hal->getMode() == MODE_LIVE) { - if (baroEnabled) { - hal->debug->println_P(PSTR("initializing baro")); - hal->baro = new BARO_CLASS; - hal->baro->Init(); - } + hal->debug->println_P(PSTR("initializing adc")); + hal->adc = new ADC_CLASS; + hal->adc->Init(); - if (compassEnabled) { - Wire.begin(); - hal->debug->println_P(PSTR("initializing compass")); - hal->compass = new COMPASS_CLASS; - hal->compass->set_orientation(compassOrientation); - hal->compass->set_offsets(0,0,0); - hal->compass->set_declination(0.0); - hal->compass->init(); - } + if (batteryMonitorEnabled) { + hal->batteryMonitor = new AP_BatteryMonitor(batteryPin,batteryVoltageDivRatio,batteryMinVolt,batteryMaxVolt); + } - /** - * Initialize ultrasonic sensors. If sensors are not plugged in, the navigator will not - * initialize them and NULL will be assigned to those corresponding pointers. - * On detecting NULL assigned to any ultrasonic sensor, its corresponding block of code - * will not be executed by the navigator. - * The coordinate system is assigned by the right hand rule with the thumb pointing down. - * In set_orientation, it is defined as (front/back,left/right,down,up) - */ + if (gpsEnabled) { + Serial1.begin(gpsBaud, 128, 16); // gps + hal->debug->println_P(PSTR("initializing gps")); + AP_GPS_Auto gpsDriver(&Serial1, &(hal->gps)); + hal->gps = &gpsDriver; + hal->gps->callback = delay; + hal->gps->init(); + } - if (rangeFinderFrontEnabled) { - hal->debug->println_P(PSTR("initializing front range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(1); - rangeFinder->set_orientation(1, 0, 0); - hal->rangeFinders.push_back(rangeFinder); - } + if (baroEnabled) { + hal->debug->println_P(PSTR("initializing baro")); + hal->baro = new BARO_CLASS; + hal->baro->Init(); + } - if (rangeFinderBackEnabled) { - hal->debug->println_P(PSTR("initializing back range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(2); - rangeFinder->set_orientation(-1, 0, 0); - hal->rangeFinders.push_back(rangeFinder); - } + if (compassEnabled) { + Wire.begin(); + hal->debug->println_P(PSTR("initializing compass")); + hal->compass = new COMPASS_CLASS; + hal->compass->set_orientation(compassOrientation); + hal->compass->set_offsets(0,0,0); + hal->compass->set_declination(0.0); + hal->compass->init(); + } - if (rangeFinderLeftEnabled) { - hal->debug->println_P(PSTR("initializing left range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(3); - rangeFinder->set_orientation(0, -1, 0); - hal->rangeFinders.push_back(rangeFinder); - } + /** + * Initialize ultrasonic sensors. If sensors are not plugged in, the navigator will not + * initialize them and NULL will be assigned to those corresponding pointers. + * On detecting NULL assigned to any ultrasonic sensor, its corresponding block of code + * will not be executed by the navigator. + * The coordinate system is assigned by the right hand rule with the thumb pointing down. + * In set_orientation, it is defined as (front/back,left/right,down,up) + */ - if (rangeFinderRightEnabled) { - hal->debug->println_P(PSTR("initializing right range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(4); - rangeFinder->set_orientation(0, 1, 0); - hal->rangeFinders.push_back(rangeFinder); - } + if (rangeFinderFrontEnabled) { + hal->debug->println_P(PSTR("initializing front range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(1); + rangeFinder->set_orientation(1, 0, 0); + hal->rangeFinders.push_back(rangeFinder); + } - if (rangeFinderUpEnabled) { - hal->debug->println_P(PSTR("initializing up range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(5); - rangeFinder->set_orientation(0, 0, -1); - hal->rangeFinders.push_back(rangeFinder); - } + if (rangeFinderBackEnabled) { + hal->debug->println_P(PSTR("initializing back range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(2); + rangeFinder->set_orientation(-1, 0, 0); + hal->rangeFinders.push_back(rangeFinder); + } - if (rangeFinderDownEnabled) { - hal->debug->println_P(PSTR("initializing down range finder")); - RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); - rangeFinder->set_analog_port(6); - rangeFinder->set_orientation(0, 0, 1); - hal->rangeFinders.push_back(rangeFinder); - } + if (rangeFinderLeftEnabled) { + hal->debug->println_P(PSTR("initializing left range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(3); + rangeFinder->set_orientation(0, -1, 0); + hal->rangeFinders.push_back(rangeFinder); + } - } + if (rangeFinderRightEnabled) { + hal->debug->println_P(PSTR("initializing right range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(4); + rangeFinder->set_orientation(0, 1, 0); + hal->rangeFinders.push_back(rangeFinder); + } - /* - * Select guidance, navigation, control algorithms - */ - navigator = new NAVIGATOR_CLASS(hal); - guide = new GUIDE_CLASS(navigator, hal); - controller = new CONTROLLER_CLASS(navigator, guide, hal); + if (rangeFinderUpEnabled) { + hal->debug->println_P(PSTR("initializing up range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(5); + rangeFinder->set_orientation(0, 0, -1); + hal->rangeFinders.push_back(rangeFinder); + } - /* - * CommLinks - */ - if (board==BOARD_ARDUPILOTMEGA_2) - { - Serial2.begin(telemBaud, 128, 128); // gcs - hal->gcs = new COMMLINK_CLASS(&Serial2, navigator, guide, controller, hal); - } - else - { - Serial3.begin(telemBaud, 128, 128); // gcs - hal->gcs = new COMMLINK_CLASS(&Serial3, navigator, guide, controller, hal); - } + if (rangeFinderDownEnabled) { + hal->debug->println_P(PSTR("initializing down range finder")); + RangeFinder * rangeFinder = new RANGE_FINDER_CLASS(hal->adc,new ModeFilter); + rangeFinder->set_analog_port(6); + rangeFinder->set_orientation(0, 0, 1); + hal->rangeFinders.push_back(rangeFinder); + } - /* - * Hardware in the Loop - */ - if (hal->getMode() == MODE_HIL_CNTL) { - Serial.println("HIL line setting up"); - Serial1.begin(hilBaud, 128, 128); - hal->hil = new COMMLINK_CLASS(&Serial1, navigator, guide, controller, hal); - } + } - /* - * Start the autopilot - */ - hal->debug->printf_P(PSTR("initializing autopilot\n")); - hal->debug->printf_P(PSTR("free ram: %d bytes\n"),freeMemory()); + /* + * Select guidance, navigation, control algorithms + */ + navigator = new NAVIGATOR_CLASS(hal); + guide = new GUIDE_CLASS(navigator, hal, velCmd, xt, xtLim); + controller = new CONTROLLER_CLASS(navigator,guide,hal); - autoPilot = new apo::AP_Autopilot(navigator, guide, controller, hal, - loopRate, loop0Rate, loop1Rate, loop2Rate, loop3Rate); + /* + * CommLinks + */ + if (board==BOARD_ARDUPILOTMEGA_2) + { + Serial2.begin(telemBaud, 128, 128); // gcs + hal->gcs = new COMMLINK_CLASS(&Serial2, navigator, guide, controller, hal); + } + else + { + Serial3.begin(telemBaud, 128, 128); // gcs + hal->gcs = new COMMLINK_CLASS(&Serial3, navigator, guide, controller, hal); + } + + /* + * Hardware in the Loop + */ + if (hal->getMode() == MODE_HIL_CNTL) { + Serial.println("HIL line setting up"); + Serial1.begin(hilBaud, 128, 128); + delay(1000); + Serial1.println("starting hil"); + hal->hil = new COMMLINK_CLASS(&Serial1, navigator, guide, controller, hal); + } + + /* + * Start the autopilot + */ + hal->debug->printf_P(PSTR("initializing autopilot\n")); + hal->debug->printf_P(PSTR("free ram: %d bytes\n"),freeMemory()); + + autoPilot = new apo::AP_Autopilot(navigator, guide, controller, hal, + loopRate, loop0Rate, loop1Rate, loop2Rate, loop3Rate); } void loop() { - autoPilot->update(); + autoPilot->update(); } #endif //_APO_COMMON_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_ArmingMechanism.cpp b/libraries/APO/AP_ArmingMechanism.cpp new file mode 100644 index 0000000000..f319a6d91e --- /dev/null +++ b/libraries/APO/AP_ArmingMechanism.cpp @@ -0,0 +1,57 @@ +/* + * AP_ArmingMechanism.cpp + * + */ + + +#include "AP_ArmingMechanism.h" +#include "AP_RcChannel.h" +#include "../FastSerial/FastSerial.h" +#include "AP_HardwareAbstractionLayer.h" +#include "AP_CommLink.h" + +namespace apo { + +void AP_ArmingMechanism::update(const float dt) { + //_hal->debug->printf_P(PSTR("ch1: %f\tch2: %f\n"),_hal->rc[_ch1]->getRadioPosition(), _hal->rc[_ch2]->getRadioPosition()); + // arming + if ( (_hal->getState() != MAV_STATE_ACTIVE) && + (fabs(_hal->rc[_ch1]->getRadioPosition()) < _ch1Min) && + (_hal->rc[_ch2]->getRadioPosition() < _ch2Min) ) { + + // always start clock at 0 + if (_armingClock<0) _armingClock = 0; + + if (_armingClock++ >= 100) { + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed")); + _hal->setState(MAV_STATE_ACTIVE); + } else { + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("arming")); + } + } + // disarming + else if ( (_hal->getState() == MAV_STATE_ACTIVE) && + (fabs(_hal->rc[_ch1]->getRadioPosition()) < _ch1Min) && + (_hal->rc[_ch2]->getRadioPosition() > _ch2Max) ) { + + // always start clock at 0 + if (_armingClock>0) _armingClock = 0; + + if (_armingClock-- <= -100) { + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed")); + _hal->setState(MAV_STATE_STANDBY); + } else { + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarming")); + } + } + // reset arming clock and report status + else if (_armingClock != 0) { + _armingClock = 0; + if (_hal->getState()==MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("armed")); + else if (_hal->getState()!=MAV_STATE_ACTIVE) _hal->gcs->sendText(SEVERITY_HIGH, PSTR("disarmed")); + } +} + +} // apo + +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_ArmingMechanism.h b/libraries/APO/AP_ArmingMechanism.h new file mode 100644 index 0000000000..e747a7831e --- /dev/null +++ b/libraries/APO/AP_ArmingMechanism.h @@ -0,0 +1,67 @@ +/* + * AP_ArmingMechanism.h + * + */ + +#ifndef AP_ARMINGMECHANISM_H_ +#define AP_ARMINGMECHANISM_H_ + +#include +#include + +namespace apo { + +class AP_HardwareAbstractionLayer; + +class AP_ArmingMechanism { + +public: + /** + * Constructor + * + * @param ch1: typically throttle channel + * @param ch2: typically yaw channel + * @param ch1Min: disarms/arms belows this + * @param ch2Min: disarms below this + * @param ch2Max: arms above this + */ + AP_ArmingMechanism(AP_HardwareAbstractionLayer * hal, + uint8_t ch1, uint8_t ch2, float ch1Min, float ch2Min, + float ch2Max) : _armingClock(0), _hal(hal), _ch1(ch1), _ch2(ch2), + _ch1Min(ch1Min), _ch2Min(ch2Min), _ch2Max(ch2Max) { + } + + /** + * update + * + * arming: + * + * to arm: put stick to bottom right for 100 controller cycles + * (max yaw, min throttle) + * + * didn't use clock here in case of millis() roll over + * for long runs + * + * disarming: + * + * to disarm: put stick to bottom left for 100 controller cycles + * (min yaw, min throttle) + */ + void update(const float dt); + +private: + + AP_HardwareAbstractionLayer * _hal; + int8_t _armingClock; + uint8_t _ch1; /// typically throttle channel + uint8_t _ch2; /// typically yaw channel + float _ch1Min; /// arms/disarms below this on ch1 + float _ch2Min; /// disarms below this on ch2 + float _ch2Max; /// arms above this on ch2 +}; + +} // namespace apo + +#endif /* AP_ARMINGMECHANISM */ + +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Autopilot.cpp b/libraries/APO/AP_Autopilot.cpp index 61a52e0ce7..07c909d637 100644 --- a/libraries/APO/AP_Autopilot.cpp +++ b/libraries/APO/AP_Autopilot.cpp @@ -5,250 +5,269 @@ * Author: jgoppert */ +/* + * AVR runtime + */ +//#include +//#include +//#include +//#include + +#include "../FastSerial/FastSerial.h" #include "AP_Autopilot.h" +#include "../AP_GPS/AP_GPS.h" +#include "../APM_RC/APM_RC.h" +#include "AP_HardwareAbstractionLayer.h" +#include "AP_CommLink.h" +#include "AP_MavlinkCommand.h" +#include "AP_Navigator.h" +#include "AP_Controller.h" +#include "AP_Guide.h" #include "AP_BatteryMonitor.h" + namespace apo { class AP_HardwareAbstractionLayer; AP_Autopilot::AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal, - float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate) : - Loop(loopRate, callback, this), _navigator(navigator), _guide(guide), - _controller(controller), _hal(hal), - callbackCalls(0) { + AP_Controller * controller, AP_HardwareAbstractionLayer * hal, + float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate) : + Loop(loopRate, callback, this), _navigator(navigator), _guide(guide), + _controller(controller), _hal(hal), + callbackCalls(0) { - hal->setState(MAV_STATE_BOOT); - hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); - hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + hal->setState(MAV_STATE_BOOT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); - /* - * Radio setup - */ - hal->debug->println_P(PSTR("initializing radio")); - APM_RC.Init(); // APM Radio initialization, + /* + * Radio setup + */ + hal->debug->println_P(PSTR("initializing radio")); + APM_RC.Init(); // APM Radio initialization, - /* - * Calibration - */ - hal->setState(MAV_STATE_CALIBRATING); - hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); - hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + /* + * Calibration + */ + hal->setState(MAV_STATE_CALIBRATING); + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); - if (navigator) navigator->calibrate(); + if (navigator) navigator->calibrate(); - /* - * Look for valid initial state - */ - while (_navigator) { - // letc gcs known we are alive - hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); - hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); - if (hal->getMode() == MODE_LIVE) { - _navigator->updateSlow(0); - if (hal->gps) { - if (hal->gps->fix) { - break; - } else { - hal->gps->update(); - hal->gcs->sendText(SEVERITY_LOW, - PSTR("waiting for gps lock\n")); - hal->debug->printf_P(PSTR("waiting for gps lock\n")); - } - } else { // no gps, can skip - break; - } - } else if (hal->getMode() == MODE_HIL_CNTL) { // hil - hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); - hal->hil->receive(); - Serial.println("HIL Receive Called"); - if (_navigator->getTimeStamp() != 0) { - // give hil a chance to send some packets - for (int i = 0; i < 5; i++) { - hal->debug->println_P(PSTR("reading initial hil packets")); - hal->gcs->sendText(SEVERITY_LOW, - PSTR("reading initial hil packets")); - delay(1000); - } - break; - } - hal->debug->println_P(PSTR("waiting for hil packet")); - } - delay(500); - } - - AP_MavlinkCommand::home.setAlt(_navigator->getAlt()); - AP_MavlinkCommand::home.setLat(_navigator->getLat()); - AP_MavlinkCommand::home.setLon(_navigator->getLon()); - AP_MavlinkCommand::home.setCommand(MAV_CMD_NAV_WAYPOINT); - AP_MavlinkCommand::home.save(); - _hal->debug->printf_P(PSTR("\nhome before load lat: %f deg, lon: %f deg, cmd: %d\n"), - AP_MavlinkCommand::home.getLat()*rad2Deg, - AP_MavlinkCommand::home.getLon()*rad2Deg, - AP_MavlinkCommand::home.getCommand()); - AP_MavlinkCommand::home.load(); - _hal->debug->printf_P(PSTR("\nhome after load lat: %f deg, lon: %f deg, cmd: %d\n"), - AP_MavlinkCommand::home.getLat()*rad2Deg, - AP_MavlinkCommand::home.getLon()*rad2Deg, - AP_MavlinkCommand::home.getCommand()); + /* + * Look for valid initial state + */ + while (_navigator) { + // letc gcs known we are alive + hal->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + if (hal->getMode() == MODE_LIVE) { + _navigator->updateSlow(0); + if (hal->gps) { + if (hal->gps->fix) { + break; + } else { + hal->gps->update(); + hal->gcs->sendText(SEVERITY_LOW, + PSTR("waiting for gps lock\n")); + hal->debug->printf_P(PSTR("waiting for gps lock\n")); + } + } else { // no gps, can skip + break; + } + } else if (hal->getMode() == MODE_HIL_CNTL) { // hil + hal->hil->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + hal->hil->receive(); + Serial.println("HIL Receive Called"); + if (_navigator->getTimeStamp() != 0) { + // give hil a chance to send some packets + for (int i = 0; i < 5; i++) { + hal->debug->println_P(PSTR("reading initial hil packets")); + hal->gcs->sendText(SEVERITY_LOW, + PSTR("reading initial hil packets")); + delay(1000); + } + break; + } + hal->debug->println_P(PSTR("waiting for hil packet")); + } + delay(500); + } - /* - * Attach loops - */ - hal->debug->println_P(PSTR("attaching loops")); - subLoops().push_back(new Loop(loop0Rate, callback0, this)); - subLoops().push_back(new Loop(loop1Rate, callback1, this)); - subLoops().push_back(new Loop(loop2Rate, callback2, this)); - subLoops().push_back(new Loop(loop3Rate, callback3, this)); + AP_MavlinkCommand::home.setAlt(_navigator->getAlt()); + AP_MavlinkCommand::home.setLat(_navigator->getLat()); + AP_MavlinkCommand::home.setLon(_navigator->getLon()); + AP_MavlinkCommand::home.setCommand(MAV_CMD_NAV_WAYPOINT); + AP_MavlinkCommand::home.save(); + _hal->debug->printf_P(PSTR("\nhome before load lat: %f deg, lon: %f deg, cmd: %d\n"), + AP_MavlinkCommand::home.getLat()*rad2Deg, + AP_MavlinkCommand::home.getLon()*rad2Deg, + AP_MavlinkCommand::home.getCommand()); + AP_MavlinkCommand::home.load(); + _hal->debug->printf_P(PSTR("\nhome after load lat: %f deg, lon: %f deg, cmd: %d\n"), + AP_MavlinkCommand::home.getLat()*rad2Deg, + AP_MavlinkCommand::home.getLon()*rad2Deg, + AP_MavlinkCommand::home.getCommand()); - hal->debug->println_P(PSTR("running")); - hal->gcs->sendText(SEVERITY_LOW, PSTR("running")); - hal->setState(MAV_STATE_STANDBY); + /* + * Attach loops, stacking for priority + */ + hal->debug->println_P(PSTR("attaching loops")); + subLoops().push_back(new Loop(loop0Rate, callback0, this)); + subLoops().push_back(new Loop(loop1Rate, callback1, this)); + subLoops().push_back(new Loop(loop2Rate, callback2, this)); + subLoops().push_back(new Loop(loop3Rate, callback3, this)); + + hal->debug->println_P(PSTR("running")); + hal->gcs->sendText(SEVERITY_LOW, PSTR("running")); + hal->setState(MAV_STATE_STANDBY); } void AP_Autopilot::callback(void * data) { - AP_Autopilot * apo = (AP_Autopilot *) data; - //apo->hal()->debug->println_P(PSTR("callback")); + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->hal()->debug->println_P(PSTR("callback")); - /* - * ahrs update - */ - apo->callbackCalls++; - if (apo->getNavigator()) - apo->getNavigator()->updateFast(apo->dt()); + /* + * ahrs update + */ + apo->callbackCalls++; + if (apo->getNavigator()) + apo->getNavigator()->updateFast(apo->dt()); } void AP_Autopilot::callback0(void * data) { - AP_Autopilot * apo = (AP_Autopilot *) data; - //apo->getHal()->debug->println_P(PSTR("callback 0")); - - /* - * hardware in the loop - */ - if (apo->getHal()->hil && apo->getHal()->getMode() != MODE_LIVE) { - apo->getHal()->hil->receive(); - apo->getHal()->hil->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); - } + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 0")); /* - * update control laws - */ - if (apo->getController()) { - //apo->getHal()->debug->println_P(PSTR("updating controller")); - apo->getController()->update(apo->subLoops()[0]->dt()); - } - /* - char msg[50]; - sprintf(msg, "c_hdg: %f, c_thr: %f", apo->guide()->headingCommand, apo->guide()->groundSpeedCommand); - apo->hal()->gcs->sendText(AP_CommLink::SEVERITY_LOW, msg); - */ + * hardware in the loop + */ + if (apo->getHal()->hil && apo->getHal()->getMode() != MODE_LIVE) { + apo->getHal()->hil->receive(); + apo->getHal()->hil->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); + } + + /* + * update control laws + */ + if (apo->getController()) { + //apo->getHal()->debug->println_P(PSTR("updating controller")); + apo->getController()->update(apo->subLoops()[0]->dt()); + } + /* + char msg[50]; + sprintf(msg, "c_hdg: %f, c_thr: %f", apo->guide()->headingCommand, apo->guide()->groundSpeedCommand); + apo->hal()->gcs->sendText(AP_CommLink::SEVERITY_LOW, msg); + */ } void AP_Autopilot::callback1(void * data) { - AP_Autopilot * apo = (AP_Autopilot *) data; - //apo->getHal()->debug->println_P(PSTR("callback 1")); - - /* - * update guidance laws - */ - if (apo->getGuide()) - { - //apo->getHal()->debug->println_P(PSTR("updating guide")); - apo->getGuide()->update(); - } + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 1")); - /* - * slow navigation loop update - */ - if (apo->getNavigator()) { - apo->getNavigator()->updateSlow(apo->subLoops()[1]->dt()); - } + /* + * update guidance laws + */ + if (apo->getGuide()) + { + //apo->getHal()->debug->println_P(PSTR("updating guide")); + apo->getGuide()->update(); + } - /* - * send telemetry - */ - if (apo->getHal()->gcs) { - apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_ATTITUDE); - } + /* + * slow navigation loop update + */ + if (apo->getNavigator()) { + apo->getNavigator()->updateSlow(apo->subLoops()[1]->dt()); + } - /* - * handle ground control station communication - */ - if (apo->getHal()->gcs) { - // send messages - apo->getHal()->gcs->requestCmds(); - apo->getHal()->gcs->sendParameters(); + /* + * send telemetry + */ + if (apo->getHal()->gcs) { + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_ATTITUDE); + } - // receive messages - apo->getHal()->gcs->receive(); - } + /* + * handle ground control station communication + */ + if (apo->getHal()->gcs) { + // send messages + apo->getHal()->gcs->requestCmds(); + apo->getHal()->gcs->sendParameters(); - /* - * navigator debug - */ - /* - if (apo->navigator()) { - apo->getHal()->debug->printf_P(PSTR("roll: %f deg\tpitch: %f deg\tyaw: %f deg\n"), - apo->navigator()->getRoll()*rad2Deg, - apo->navigator()->getPitch()*rad2Deg, - apo->navigator()->getYaw()*rad2Deg); - apo->getHal()->debug->printf_P(PSTR("lat: %f deg\tlon: %f deg\talt: %f m\n"), - apo->navigator()->getLat()*rad2Deg, - apo->navigator()->getLon()*rad2Deg, - apo->navigator()->getAlt()); - } - */ + // receive messages + apo->getHal()->gcs->receive(); + } + + /* + * navigator debug + */ + /* + if (apo->navigator()) { + apo->getHal()->debug->printf_P(PSTR("roll: %f deg\tpitch: %f deg\tyaw: %f deg\n"), + apo->navigator()->getRoll()*rad2Deg, + apo->navigator()->getPitch()*rad2Deg, + apo->navigator()->getYaw()*rad2Deg); + apo->getHal()->debug->printf_P(PSTR("lat: %f deg\tlon: %f deg\talt: %f m\n"), + apo->navigator()->getLat()*rad2Deg, + apo->navigator()->getLon()*rad2Deg, + apo->navigator()->getAlt()); + } + */ } void AP_Autopilot::callback2(void * data) { - AP_Autopilot * apo = (AP_Autopilot *) data; - //apo->getHal()->debug->println_P(PSTR("callback 2")); - - /* - * send telemetry - */ - if (apo->getHal()->gcs) { - // send messages - apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW); - //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); - //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION); - //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW); - //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU); - } + AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 2")); - /* - * update battery monitor - */ - if (apo->getHal()->batteryMonitor) apo->getHal()->batteryMonitor->update(); + /* + * send telemetry + */ + if (apo->getHal()->gcs) { + // send messages + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GPS_RAW); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_SCALED); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_RC_CHANNELS_RAW); + //apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_GLOBAL_POSITION); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SCALED_IMU); + } - /* - * send heartbeat - */ - apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); + /* + * update battery monitor + */ + if (apo->getHal()->batteryMonitor) apo->getHal()->batteryMonitor->update(); - /* - * load/loop rate/ram debug - */ - apo->getHal()->load = apo->load(); - apo->getHal()->debug->printf_P(PSTR("callback calls: %d\n"),apo->callbackCalls); - apo->callbackCalls = 0; - apo->getHal()->debug->printf_P(PSTR("load: %d%%\trate: %f Hz\tfree ram: %d bytes\n"), - apo->load(),1.0/apo->dt(),freeMemory()); - apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + /* + * send heartbeat + */ + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_HEARTBEAT); - /* - * adc debug - */ - //apo->getDebug().printf_P(PSTR("adc: %d %d %d %d %d %d %d %d\n"), - //apo->adc()->Ch(0), apo->adc()->Ch(1), apo->adc()->Ch(2), - //apo->adc()->Ch(3), apo->adc()->Ch(4), apo->adc()->Ch(5), - //apo->adc()->Ch(6), apo->adc()->Ch(7), apo->adc()->Ch(8)); + /* + * load/loop rate/ram debug + */ + apo->getHal()->load = apo->load(); + apo->getHal()->debug->printf_P(PSTR("callback calls: %d\n"),apo->callbackCalls); + apo->callbackCalls = 0; + apo->getHal()->debug->printf_P(PSTR("load: %d%%\trate: %f Hz\tfree ram: %d bytes\n"), + apo->load(),1.0/apo->dt(),freeMemory()); + apo->getHal()->gcs->sendMessage(MAVLINK_MSG_ID_SYS_STATUS); + + /* + * adc debug + */ + //apo->getDebug().printf_P(PSTR("adc: %d %d %d %d %d %d %d %d\n"), + //apo->adc()->Ch(0), apo->adc()->Ch(1), apo->adc()->Ch(2), + //apo->adc()->Ch(3), apo->adc()->Ch(4), apo->adc()->Ch(5), + //apo->adc()->Ch(6), apo->adc()->Ch(7), apo->adc()->Ch(8)); } void AP_Autopilot::callback3(void * data) { - //AP_Autopilot * apo = (AP_Autopilot *) data; - //apo->getHal()->debug->println_P(PSTR("callback 3")); + //AP_Autopilot * apo = (AP_Autopilot *) data; + //apo->getHal()->debug->println_P(PSTR("callback 3")); } } // apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Autopilot.h b/libraries/APO/AP_Autopilot.h index e6684fe07f..b48737d81b 100644 --- a/libraries/APO/AP_Autopilot.h +++ b/libraries/APO/AP_Autopilot.h @@ -8,38 +8,7 @@ #ifndef AP_AUTOPILOT_H_ #define AP_AUTOPILOT_H_ -/* - * AVR runtime - */ -#include -#include -#include -#include -/* - * Libraries - */ -#include "../AP_Common/AP_Common.h" -#include "../FastSerial/FastSerial.h" -#include "../AP_GPS/GPS.h" -#include "../APM_RC/APM_RC.h" -#include "../AP_ADC/AP_ADC.h" -#include "../APM_BMP085/APM_BMP085.h" -#include "../AP_Compass/AP_Compass.h" -#include "../AP_Math/AP_Math.h" -#include "../AP_IMU/AP_IMU.h" -#include "../AP_DCM/AP_DCM.h" #include "../AP_Common/AP_Loop.h" -#include "../GCS_MAVLink/GCS_MAVLink.h" -#include "../AP_RangeFinder/AP_RangeFinder.h" -/* - * Local Modules - */ -#include "AP_HardwareAbstractionLayer.h" -#include "AP_RcChannel.h" -#include "AP_Controller.h" -#include "AP_Navigator.h" -#include "AP_Guide.h" -#include "AP_CommLink.h" /** * ArduPilotOne namespace to protect variables @@ -50,7 +19,10 @@ namespace apo { // forward declarations -class AP_CommLink; +class AP_Navigator; +class AP_Guide; +class AP_Controller; +class AP_HardwareAbstractionLayer; /** * This class encapsulates the entire autopilot system @@ -65,90 +37,91 @@ class AP_CommLink; */ class AP_Autopilot: public Loop { public: - /** - * Default constructor - */ - AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal, - float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate); + /** + * Default constructor + */ + AP_Autopilot(AP_Navigator * navigator, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal, + float loopRate, float loop0Rate, float loop1Rate, float loop2Rate, float loop3Rate); - /** - * Accessors - */ - AP_Navigator * getNavigator() { - return _navigator; - } - AP_Guide * getGuide() { - return _guide; - } - AP_Controller * getController() { - return _controller; - } - AP_HardwareAbstractionLayer * getHal() { - return _hal; - } + /** + * Accessors + */ + AP_Navigator * getNavigator() { + return _navigator; + } + AP_Guide * getGuide() { + return _guide; + } + AP_Controller * getController() { + return _controller; + } + AP_HardwareAbstractionLayer * getHal() { + return _hal; + } - /** - * Loop Monitoring - */ - uint32_t callbackCalls; + /** + * Loop Monitoring + */ + uint32_t callbackCalls; private: - /** - * Loop Callbacks (fastest) - * - inertial navigation - * @param data A void pointer used to pass the apo class - * so that the apo public interface may be accessed. - */ - static void callback(void * data); + /** + * Loop Callbacks (fastest) + * - inertial navigation + * @param data A void pointer used to pass the apo class + * so that the apo public interface may be accessed. + */ + static void callback(void * data); - /** - * Loop 0 Callbacks - * - control - * - compass reading - * @see callback - */ - static void callback0(void * data); + /** + * Loop 0 Callbacks + * - control + * - compass reading + * @see callback + */ + static void callback0(void * data); - /** - * Loop 1 Callbacks - * - gps sensor fusion - * - compass sensor fusion - * @see callback - */ - static void callback1(void * data); + /** + * Loop 1 Callbacks + * - gps sensor fusion + * - compass sensor fusion + * @see callback + */ + static void callback1(void * data); - /** - * Loop 2 Callbacks - * - slow messages - * @see callback - */ - static void callback2(void * data); + /** + * Loop 2 Callbacks + * - slow messages + * @see callback + */ + static void callback2(void * data); - /** - * Loop 3 Callbacks - * - super slow messages - * - log writing - * @see callback - */ - static void callback3(void * data); + /** + * Loop 3 Callbacks + * - super slow messages + * - log writing + * @see callback + */ + static void callback3(void * data); - /** - * Components - */ - AP_Navigator * _navigator; - AP_Guide * _guide; - AP_Controller * _controller; - AP_HardwareAbstractionLayer * _hal; + /** + * Components + */ + AP_Navigator * _navigator; + AP_Guide * _guide; + AP_Controller * _controller; + AP_HardwareAbstractionLayer * _hal; - /** - * Constants - */ - static const float deg2rad = M_PI / 180; - static const float rad2deg = 180 / M_PI; + /** + * Constants + */ + static const float deg2rad = M_PI / 180; + static const float rad2deg = 180 / M_PI; }; } // namespace apo #endif /* AP_AUTOPILOT_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_BatteryMonitor.cpp b/libraries/APO/AP_BatteryMonitor.cpp index e5550d2798..835f3072d2 100644 --- a/libraries/APO/AP_BatteryMonitor.cpp +++ b/libraries/APO/AP_BatteryMonitor.cpp @@ -8,3 +8,5 @@ namespace apo { } // apo + +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_BatteryMonitor.h b/libraries/APO/AP_BatteryMonitor.h index 7f82db349d..359320a368 100644 --- a/libraries/APO/AP_BatteryMonitor.h +++ b/libraries/APO/AP_BatteryMonitor.h @@ -13,39 +13,40 @@ namespace apo { class AP_BatteryMonitor { public: - AP_BatteryMonitor(uint8_t pin, float voltageDivRatio, float minVolt, float maxVolt) : - _pin(pin), _voltageDivRatio(voltageDivRatio), - _minVolt(minVolt), _maxVolt(maxVolt), _voltage(maxVolt) { - } + AP_BatteryMonitor(uint8_t pin, float voltageDivRatio, float minVolt, float maxVolt) : + _pin(pin), _voltageDivRatio(voltageDivRatio), + _minVolt(minVolt), _maxVolt(maxVolt), _voltage(maxVolt) { + } - void update() { - // low pass filter on voltage - _voltage = _voltage*.9 + (analogRead(_pin)/255)*_voltageDivRatio*0.1; - } + void update() { + // low pass filter on voltage + _voltage = _voltage*.9 + (analogRead(_pin)/255)*_voltageDivRatio*0.1; + } - /** - * Accessors - */ - float getVoltage() { - return _voltage; - } + /** + * Accessors + */ + float getVoltage() { + return _voltage; + } - uint8_t getPercentage() { - float norm = (_voltage-_minVolt)/(_maxVolt-_minVolt); - if (norm < 0) norm = 0; - else if (norm > 1) norm = 1; - return 100*norm; - } + uint8_t getPercentage() { + float norm = (_voltage-_minVolt)/(_maxVolt-_minVolt); + if (norm < 0) norm = 0; + else if (norm > 1) norm = 1; + return 100*norm; + } private: - uint8_t _pin; - float _voltageDivRatio; - float _voltage; - float _minVolt; - float _maxVolt; + uint8_t _pin; + float _voltageDivRatio; + float _voltage; + float _minVolt; + float _maxVolt; }; } // namespace apo #endif /* AP_BATTERYMONITOR_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_CommLink.cpp b/libraries/APO/AP_CommLink.cpp index cad558ccbd..a18b91594a 100644 --- a/libraries/APO/AP_CommLink.cpp +++ b/libraries/APO/AP_CommLink.cpp @@ -10,6 +10,7 @@ #include "AP_Navigator.h" #include "AP_Guide.h" #include "AP_Controller.h" +#include "AP_MavlinkCommand.h" #include "AP_HardwareAbstractionLayer.h" #include "AP_RcChannel.h" #include "../AP_GPS/AP_GPS.h" @@ -24,225 +25,225 @@ uint8_t MavlinkComm::_nChannels = 0; uint8_t MavlinkComm::_paramNameLengthMax = 13; AP_CommLink::AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : - _link(link), _navigator(navigator), _guide(guide), - _controller(controller), _hal(hal) { + AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : + _link(link), _navigator(navigator), _guide(guide), + _controller(controller), _hal(hal) { } MavlinkComm::MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : - AP_CommLink(link, nav, guide, controller, hal), + AP_Controller * controller, AP_HardwareAbstractionLayer * hal) : + AP_CommLink(link, nav, guide, controller, hal), - // options - _useRelativeAlt(true), + // options + _useRelativeAlt(true), - // commands - _sendingCmds(false), _receivingCmds(false), - _cmdTimeLastSent(millis()), _cmdTimeLastReceived(millis()), - _cmdDestSysId(0), _cmdDestCompId(0), _cmdRequestIndex(0), - _cmdMax(30), _cmdNumberRequested(0), + // commands + _sendingCmds(false), _receivingCmds(false), + _cmdTimeLastSent(millis()), _cmdTimeLastReceived(millis()), + _cmdDestSysId(0), _cmdDestCompId(0), _cmdRequestIndex(0), + _cmdMax(30), _cmdNumberRequested(0), - // parameters - _parameterCount(0), _queuedParameter(NULL), - _queuedParameterIndex(0) { + // parameters + _parameterCount(0), _queuedParameter(NULL), + _queuedParameterIndex(0) { - switch (_nChannels) { - case 0: - mavlink_comm_0_port = link; - _channel = MAVLINK_COMM_0; - _nChannels++; - break; - case 1: - mavlink_comm_1_port = link; - _channel = MAVLINK_COMM_1; - _nChannels++; - break; - default: - // signal that number of channels exceeded - _channel = MAVLINK_COMM_3; - break; - } + switch (_nChannels) { + case 0: + mavlink_comm_0_port = link; + _channel = MAVLINK_COMM_0; + _nChannels++; + break; + case 1: + mavlink_comm_1_port = link; + _channel = MAVLINK_COMM_1; + _nChannels++; + break; + default: + // signal that number of channels exceeded + _channel = MAVLINK_COMM_3; + break; + } } void MavlinkComm::send() { - // if number of channels exceeded return - if (_channel == MAVLINK_COMM_3) - return; + // if number of channels exceeded return + if (_channel == MAVLINK_COMM_3) + return; } void MavlinkComm::sendMessage(uint8_t id, uint32_t param) { - //_hal->debug->printf_P(PSTR("send message\n")); + //_hal->debug->printf_P(PSTR("send message\n")); - // if number of channels exceeded return - if (_channel == MAVLINK_COMM_3) - return; + // if number of channels exceeded return + if (_channel == MAVLINK_COMM_3) + return; - uint64_t timeStamp = micros(); + uint64_t timeStamp = micros(); - switch (id) { + switch (id) { - case MAVLINK_MSG_ID_HEARTBEAT: { - mavlink_msg_heartbeat_send(_channel, mavlink_system.type, - MAV_AUTOPILOT_ARDUPILOTMEGA); - break; - } + case MAVLINK_MSG_ID_HEARTBEAT: { + mavlink_msg_heartbeat_send(_channel, mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + break; + } - case MAVLINK_MSG_ID_ATTITUDE: { - mavlink_msg_attitude_send(_channel, timeStamp, - _navigator->getRoll(), _navigator->getPitch(), - _navigator->getYaw(), _navigator->getRollRate(), - _navigator->getPitchRate(), _navigator->getYawRate()); - break; - } + case MAVLINK_MSG_ID_ATTITUDE: { + mavlink_msg_attitude_send(_channel, timeStamp, + _navigator->getRoll(), _navigator->getPitch(), + _navigator->getYaw(), _navigator->getRollRate(), + _navigator->getPitchRate(), _navigator->getYawRate()); + break; + } - case MAVLINK_MSG_ID_GLOBAL_POSITION: { - mavlink_msg_global_position_send(_channel, timeStamp, - _navigator->getLat() * rad2Deg, - _navigator->getLon() * rad2Deg, _navigator->getAlt(), - _navigator->getVN(), _navigator->getVE(), - _navigator->getVD()); - break; - } + case MAVLINK_MSG_ID_GLOBAL_POSITION: { + mavlink_msg_global_position_send(_channel, timeStamp, + _navigator->getLat() * rad2Deg, + _navigator->getLon() * rad2Deg, _navigator->getAlt(), + _navigator->getVN(), _navigator->getVE(), + _navigator->getVD()); + break; + } - case MAVLINK_MSG_ID_GPS_RAW: { - mavlink_msg_gps_raw_send(_channel, timeStamp, _hal->gps->status(), - _navigator->getLat() * rad2Deg, - _navigator->getLon() * rad2Deg, _navigator->getAlt(), 0, 0, - _navigator->getGroundSpeed(), - _navigator->getYaw() * rad2Deg); - break; - } + case MAVLINK_MSG_ID_GPS_RAW: { + mavlink_msg_gps_raw_send(_channel, timeStamp, _hal->gps->status(), + _navigator->getLat() * rad2Deg, + _navigator->getLon() * rad2Deg, _navigator->getAlt(), 0, 0, + _navigator->getGroundSpeed(), + _navigator->getYaw() * rad2Deg); + break; + } - /* - case MAVLINK_MSG_ID_GPS_RAW_INT: { - mavlink_msg_gps_raw_int_send(_channel,timeStamp,_hal->gps->status(), - _navigator->getLat_degInt(), _navigator->getLon_degInt(),_navigator->getAlt_intM(), 0,0, - _navigator->getGroundSpeed(),_navigator->getYaw()*rad2Deg); - break; - } - */ + /* + case MAVLINK_MSG_ID_GPS_RAW_INT: { + mavlink_msg_gps_raw_int_send(_channel,timeStamp,_hal->gps->status(), + _navigator->getLat_degInt(), _navigator->getLon_degInt(),_navigator->getAlt_intM(), 0,0, + _navigator->getGroundSpeed(),_navigator->getYaw()*rad2Deg); + break; + } + */ - case MAVLINK_MSG_ID_SCALED_IMU: { - /* - * accel/gyro debug - */ - /* - Vector3f accel = _hal->imu->get_accel(); - Vector3f gyro = _hal->imu->get_gyro(); - Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), - accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); - */ - Vector3f accel = _hal->imu->get_accel(); - Vector3f gyro = _hal->imu->get_gyro(); - mavlink_msg_raw_imu_send(_channel, timeStamp, 1000 * accel.x, - 1000 * accel.y, 1000 * accel.z, 1000 * gyro.x, - 1000 * gyro.y, 1000 * gyro.z, _hal->compass->mag_x, - _hal->compass->mag_y, _hal->compass->mag_z); // XXX THIS IS NOT SCALED FOR MAG - } + case MAVLINK_MSG_ID_SCALED_IMU: { + /* + * accel/gyro debug + */ + /* + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), + accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); + */ + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + mavlink_msg_raw_imu_send(_channel, timeStamp, 1000 * accel.x, + 1000 * accel.y, 1000 * accel.z, 1000 * gyro.x, + 1000 * gyro.y, 1000 * gyro.z, _hal->compass->mag_x, + _hal->compass->mag_y, _hal->compass->mag_z); // XXX THIS IS NOT SCALED FOR MAG + } - case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: { - int16_t ch[8]; - for (int i = 0; i < 8; i++) - ch[i] = 0; - for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) { - ch[i] = 10000 * _hal->rc[i]->getPosition(); - //_hal->debug->printf_P(PSTR("ch: %d position: %d\n"),i,ch[i]); - } - mavlink_msg_rc_channels_scaled_send(_channel, ch[0], ch[1], ch[2], - ch[3], ch[4], ch[5], ch[6], ch[7], 255); - break; - } + case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: { + int16_t ch[8]; + for (int i = 0; i < 8; i++) + ch[i] = 0; + for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) { + ch[i] = 10000 * _hal->rc[i]->getPosition(); + //_hal->debug->printf_P(PSTR("ch: %d position: %d\n"),i,ch[i]); + } + mavlink_msg_rc_channels_scaled_send(_channel, ch[0], ch[1], ch[2], + ch[3], ch[4], ch[5], ch[6], ch[7], 255); + break; + } - case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { - int16_t ch[8]; - for (int i = 0; i < 8; i++) - ch[i] = 0; - for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) - ch[i] = _hal->rc[i]->getPwm(); - mavlink_msg_rc_channels_raw_send(_channel, ch[0], ch[1], ch[2], - ch[3], ch[4], ch[5], ch[6], ch[7], 255); - break; - } + case MAVLINK_MSG_ID_RC_CHANNELS_RAW: { + int16_t ch[8]; + for (int i = 0; i < 8; i++) + ch[i] = 0; + for (uint8_t i = 0; i < 8 && i < _hal->rc.getSize(); i++) + ch[i] = _hal->rc[i]->getPwm(); + mavlink_msg_rc_channels_raw_send(_channel, ch[0], ch[1], ch[2], + ch[3], ch[4], ch[5], ch[6], ch[7], 255); + break; + } - case MAVLINK_MSG_ID_SYS_STATUS: { + case MAVLINK_MSG_ID_SYS_STATUS: { - uint16_t batteryVoltage = 0; // (milli volts) - uint16_t batteryPercentage = 1000; // times 10 - if (_hal->batteryMonitor) { - batteryPercentage = _hal->batteryMonitor->getPercentage()*10; - batteryVoltage = _hal->batteryMonitor->getVoltage()*1000; - } - mavlink_msg_sys_status_send(_channel, _controller->getMode(), - _guide->getMode(), _hal->getState(), _hal->load * 10, - batteryVoltage, batteryPercentage, _packetDrops); - break; - } + uint16_t batteryVoltage = 0; // (milli volts) + uint16_t batteryPercentage = 1000; // times 10 + if (_hal->batteryMonitor) { + batteryPercentage = _hal->batteryMonitor->getPercentage()*10; + batteryVoltage = _hal->batteryMonitor->getVoltage()*1000; + } + mavlink_msg_sys_status_send(_channel, _controller->getMode(), + _guide->getMode(), _hal->getState(), _hal->load * 10, + batteryVoltage, batteryPercentage, _packetDrops); + break; + } - case MAVLINK_MSG_ID_WAYPOINT_ACK: { - sendText(SEVERITY_LOW, PSTR("waypoint ack")); - //mavlink_waypoint_ack_t packet; - uint8_t type = 0; // ok (0), error(1) - mavlink_msg_waypoint_ack_send(_channel, _cmdDestSysId, - _cmdDestCompId, type); + case MAVLINK_MSG_ID_WAYPOINT_ACK: { + sendText(SEVERITY_LOW, PSTR("waypoint ack")); + //mavlink_waypoint_ack_t packet; + uint8_t type = 0; // ok (0), error(1) + mavlink_msg_waypoint_ack_send(_channel, _cmdDestSysId, + _cmdDestCompId, type); - // turn off waypoint send - _receivingCmds = false; - break; - } + // turn off waypoint send + _receivingCmds = false; + break; + } - case MAVLINK_MSG_ID_WAYPOINT_CURRENT: { - mavlink_msg_waypoint_current_send(_channel, - _guide->getCurrentIndex()); - break; - } + case MAVLINK_MSG_ID_WAYPOINT_CURRENT: { + mavlink_msg_waypoint_current_send(_channel, + _guide->getCurrentIndex()); + break; + } - default: { - char msg[50]; - sprintf(msg, "autopilot sending unknown command with id: %d", id); - sendText(SEVERITY_HIGH, msg); - } + default: { + char msg[50]; + sprintf(msg, "autopilot sending unknown command with id: %d", id); + sendText(SEVERITY_HIGH, msg); + } - } // switch + } // switch } // send message void MavlinkComm::receive() { - //_hal->debug->printf_P(PSTR("receive\n")); - // if number of channels exceeded return - // - if (_channel == MAVLINK_COMM_3) - return; + //_hal->debug->printf_P(PSTR("receive\n")); + // if number of channels exceeded return + // + if (_channel == MAVLINK_COMM_3) + return; - // receive new packets - mavlink_message_t msg; - mavlink_status_t status; - status.packet_rx_drop_count = 0; + // receive new packets + mavlink_message_t msg; + mavlink_status_t status; + status.packet_rx_drop_count = 0; - // process received bytes - while (comm_get_available(_channel)) { - uint8_t c = comm_receive_ch(_channel); + // process received bytes + while (comm_get_available(_channel)) { + uint8_t c = comm_receive_ch(_channel); - // Try to get a new message - if (mavlink_parse_char(_channel, c, &msg, &status)) - _handleMessage(&msg); - } + // Try to get a new message + if (mavlink_parse_char(_channel, c, &msg, &status)) + _handleMessage(&msg); + } - // Update packet drops counter - _packetDrops += status.packet_rx_drop_count; + // Update packet drops counter + _packetDrops += status.packet_rx_drop_count; } void MavlinkComm::sendText(uint8_t severity, const char *str) { - mavlink_msg_statustext_send(_channel, severity, (const int8_t*) str); + mavlink_msg_statustext_send(_channel, severity, (const int8_t*) str); } void MavlinkComm::sendText(uint8_t severity, const prog_char_t *str) { - mavlink_statustext_t m; - uint8_t i; - for (i = 0; i < sizeof(m.text); i++) { - m.text[i] = pgm_read_byte((const prog_char *) (str++)); - } - if (i < sizeof(m.text)) - m.text[i] = 0; - sendText(severity, (const char *) m.text); + mavlink_statustext_t m; + uint8_t i; + for (i = 0; i < sizeof(m.text); i++) { + m.text[i] = pgm_read_byte((const prog_char *) (str++)); + } + if (i < sizeof(m.text)) + m.text[i] = 0; + sendText(severity, (const char *) m.text); } void MavlinkComm::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) { @@ -252,30 +253,30 @@ void MavlinkComm::acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) { * sends parameters one at a time */ void MavlinkComm::sendParameters() { - //_hal->debug->printf_P(PSTR("send parameters\n")); - // Check to see if we are sending parameters - while (NULL != _queuedParameter) { - AP_Var *vp; - float value; + //_hal->debug->printf_P(PSTR("send parameters\n")); + // Check to see if we are sending parameters + while (NULL != _queuedParameter) { + AP_Var *vp; + float value; - // copy the current parameter and prepare to move to the next - vp = _queuedParameter; - _queuedParameter = _queuedParameter->next(); + // copy the current parameter and prepare to move to the next + vp = _queuedParameter; + _queuedParameter = _queuedParameter->next(); - // if the parameter can be cast to float, report it here and break out of the loop - value = vp->cast_to_float(); - if (!isnan(value)) { + // if the parameter can be cast to float, report it here and break out of the loop + value = vp->cast_to_float(); + if (!isnan(value)) { - char paramName[_paramNameLengthMax]; - vp->copy_name(paramName, sizeof(paramName)); + char paramName[_paramNameLengthMax]; + vp->copy_name(paramName, sizeof(paramName)); - mavlink_msg_param_value_send(_channel, (int8_t*) paramName, - value, _countParameters(), _queuedParameterIndex); + mavlink_msg_param_value_send(_channel, (int8_t*) paramName, + value, _countParameters(), _queuedParameterIndex); - _queuedParameterIndex++; - break; - } - } + _queuedParameterIndex++; + break; + } + } } @@ -283,439 +284,440 @@ void MavlinkComm::sendParameters() { * request commands one at a time */ void MavlinkComm::requestCmds() { - //_hal->debug->printf_P(PSTR("requesting commands\n")); - // request cmds one by one - if (_receivingCmds && _cmdRequestIndex <= _cmdNumberRequested) { - mavlink_msg_waypoint_request_send(_channel, _cmdDestSysId, - _cmdDestCompId, _cmdRequestIndex); - } + //_hal->debug->printf_P(PSTR("requesting commands\n")); + // request cmds one by one + if (_receivingCmds && _cmdRequestIndex <= _cmdNumberRequested) { + mavlink_msg_waypoint_request_send(_channel, _cmdDestSysId, + _cmdDestCompId, _cmdRequestIndex); + } } void MavlinkComm::_handleMessage(mavlink_message_t * msg) { - uint32_t timeStamp = micros(); + uint32_t timeStamp = micros(); - switch (msg->msgid) { - _hal->debug->printf_P(PSTR("message received: %d"), msg->msgid); + switch (msg->msgid) { + _hal->debug->printf_P(PSTR("message received: %d"), msg->msgid); - case MAVLINK_MSG_ID_HEARTBEAT: { - mavlink_heartbeat_t packet; - mavlink_msg_heartbeat_decode(msg, &packet); - _hal->lastHeartBeat = micros(); - break; - } + case MAVLINK_MSG_ID_HEARTBEAT: { + mavlink_heartbeat_t packet; + mavlink_msg_heartbeat_decode(msg, &packet); + _hal->lastHeartBeat = micros(); + break; + } - case MAVLINK_MSG_ID_GPS_RAW: { - // decode - mavlink_gps_raw_t packet; - mavlink_msg_gps_raw_decode(msg, &packet); + case MAVLINK_MSG_ID_GPS_RAW: { + // decode + mavlink_gps_raw_t packet; + mavlink_msg_gps_raw_decode(msg, &packet); - _navigator->setTimeStamp(timeStamp); - _navigator->setLat(packet.lat * deg2Rad); - _navigator->setLon(packet.lon * deg2Rad); - _navigator->setAlt(packet.alt); - _navigator->setYaw(packet.hdg * deg2Rad); - _navigator->setGroundSpeed(packet.v); - _navigator->setAirSpeed(packet.v); - //_hal->debug->printf_P(PSTR("received hil gps raw packet\n")); - /* - _hal->debug->printf_P(PSTR("received lat: %f deg\tlon: %f deg\talt: %f m\n"), - packet.lat, - packet.lon, - packet.alt); - */ - break; - } + _navigator->setTimeStamp(timeStamp); + _navigator->setLat(packet.lat * deg2Rad); + _navigator->setLon(packet.lon * deg2Rad); + _navigator->setAlt(packet.alt); + _navigator->setYaw(packet.hdg * deg2Rad); + _navigator->setGroundSpeed(packet.v); + _navigator->setAirSpeed(packet.v); + //_hal->debug->printf_P(PSTR("received hil gps raw packet\n")); + /* + _hal->debug->printf_P(PSTR("received lat: %f deg\tlon: %f deg\talt: %f m\n"), + packet.lat, + packet.lon, + packet.alt); + */ + break; + } - case MAVLINK_MSG_ID_ATTITUDE: { - // decode - mavlink_attitude_t packet; - mavlink_msg_attitude_decode(msg, &packet); + case MAVLINK_MSG_ID_ATTITUDE: { + // decode + mavlink_attitude_t packet; + mavlink_msg_attitude_decode(msg, &packet); - // set dcm hil sensor - _navigator->setTimeStamp(timeStamp); - _navigator->setRoll(packet.roll); - _navigator->setPitch(packet.pitch); - _navigator->setYaw(packet.yaw); - _navigator->setRollRate(packet.rollspeed); - _navigator->setPitchRate(packet.pitchspeed); - _navigator->setYawRate(packet.yawspeed); - //_hal->debug->printf_P(PSTR("received hil attitude packet\n")); - break; - } + // set dcm hil sensor + _navigator->setTimeStamp(timeStamp); + _navigator->setRoll(packet.roll); + _navigator->setPitch(packet.pitch); + _navigator->setYaw(packet.yaw); + _navigator->setRollRate(packet.rollspeed); + _navigator->setPitchRate(packet.pitchspeed); + _navigator->setYawRate(packet.yawspeed); + //_hal->debug->printf_P(PSTR("received hil attitude packet\n")); + break; + } - case MAVLINK_MSG_ID_ACTION: { - // decode - mavlink_action_t packet; - mavlink_msg_action_decode(msg, &packet); - if (_checkTarget(packet.target, packet.target_component)) - break; + case MAVLINK_MSG_ID_ACTION: { + // decode + mavlink_action_t packet; + mavlink_msg_action_decode(msg, &packet); + if (_checkTarget(packet.target, packet.target_component)) + break; - // do action - sendText(SEVERITY_LOW, PSTR("action received")); - switch (packet.action) { + // do action + sendText(SEVERITY_LOW, PSTR("action received")); + switch (packet.action) { - case MAV_ACTION_STORAGE_READ: - AP_Var::load_all(); - break; + case MAV_ACTION_STORAGE_READ: + AP_Var::load_all(); + break; - case MAV_ACTION_STORAGE_WRITE: - AP_Var::save_all(); - break; + case MAV_ACTION_STORAGE_WRITE: + AP_Var::save_all(); + break; - case MAV_ACTION_CALIBRATE_RC: - case MAV_ACTION_CALIBRATE_GYRO: - case MAV_ACTION_CALIBRATE_MAG: - case MAV_ACTION_CALIBRATE_ACC: - case MAV_ACTION_CALIBRATE_PRESSURE: - case MAV_ACTION_REBOOT: - case MAV_ACTION_REC_START: - case MAV_ACTION_REC_PAUSE: - case MAV_ACTION_REC_STOP: - case MAV_ACTION_TAKEOFF: - case MAV_ACTION_LAND: - case MAV_ACTION_NAVIGATE: - case MAV_ACTION_LOITER: - case MAV_ACTION_MOTORS_START: - case MAV_ACTION_CONFIRM_KILL: - case MAV_ACTION_EMCY_KILL: - case MAV_ACTION_MOTORS_STOP: - case MAV_ACTION_SHUTDOWN: - case MAV_ACTION_CONTINUE: - case MAV_ACTION_SET_MANUAL: - case MAV_ACTION_SET_AUTO: - case MAV_ACTION_LAUNCH: - case MAV_ACTION_RETURN: - case MAV_ACTION_EMCY_LAND: - case MAV_ACTION_HALT: - sendText(SEVERITY_LOW, PSTR("action not implemented")); - break; - default: - sendText(SEVERITY_LOW, PSTR("unknown action")); - break; - } - break; - } + case MAV_ACTION_CALIBRATE_RC: + case MAV_ACTION_CALIBRATE_GYRO: + case MAV_ACTION_CALIBRATE_MAG: + case MAV_ACTION_CALIBRATE_ACC: + case MAV_ACTION_CALIBRATE_PRESSURE: + case MAV_ACTION_REBOOT: + case MAV_ACTION_REC_START: + case MAV_ACTION_REC_PAUSE: + case MAV_ACTION_REC_STOP: + case MAV_ACTION_TAKEOFF: + case MAV_ACTION_LAND: + case MAV_ACTION_NAVIGATE: + case MAV_ACTION_LOITER: + case MAV_ACTION_MOTORS_START: + case MAV_ACTION_CONFIRM_KILL: + case MAV_ACTION_EMCY_KILL: + case MAV_ACTION_MOTORS_STOP: + case MAV_ACTION_SHUTDOWN: + case MAV_ACTION_CONTINUE: + case MAV_ACTION_SET_MANUAL: + case MAV_ACTION_SET_AUTO: + case MAV_ACTION_LAUNCH: + case MAV_ACTION_RETURN: + case MAV_ACTION_EMCY_LAND: + case MAV_ACTION_HALT: + sendText(SEVERITY_LOW, PSTR("action not implemented")); + break; + default: + sendText(SEVERITY_LOW, PSTR("unknown action")); + break; + } + break; + } - case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: { - sendText(SEVERITY_LOW, PSTR("waypoint request list")); + case MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST: { + sendText(SEVERITY_LOW, PSTR("waypoint request list")); - // decode - mavlink_waypoint_request_list_t packet; - mavlink_msg_waypoint_request_list_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_request_list_t packet; + mavlink_msg_waypoint_request_list_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // Start sending waypoints - mavlink_msg_waypoint_count_send(_channel, msg->sysid, msg->compid, - _guide->getNumberOfCommands()); + // Start sending waypoints + mavlink_msg_waypoint_count_send(_channel, msg->sysid, msg->compid, + _guide->getNumberOfCommands()); - _cmdTimeLastSent = millis(); - _cmdTimeLastReceived = millis(); - _sendingCmds = true; - _receivingCmds = false; - _cmdDestSysId = msg->sysid; - _cmdDestCompId = msg->compid; - break; - } + _cmdTimeLastSent = millis(); + _cmdTimeLastReceived = millis(); + _sendingCmds = true; + _receivingCmds = false; + _cmdDestSysId = msg->sysid; + _cmdDestCompId = msg->compid; + break; + } - case MAVLINK_MSG_ID_WAYPOINT_REQUEST: { - sendText(SEVERITY_LOW, PSTR("waypoint request")); + case MAVLINK_MSG_ID_WAYPOINT_REQUEST: { + sendText(SEVERITY_LOW, PSTR("waypoint request")); - // Check if sending waypiont - if (!_sendingCmds) - break; + // Check if sending waypiont + if (!_sendingCmds) + break; - // decode - mavlink_waypoint_request_t packet; - mavlink_msg_waypoint_request_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_request_t packet; + mavlink_msg_waypoint_request_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - _hal->debug->printf_P(PSTR("sequence: %d\n"),packet.seq); - AP_MavlinkCommand cmd(packet.seq); + _hal->debug->printf_P(PSTR("sequence: %d\n"),packet.seq); + AP_MavlinkCommand cmd(packet.seq); - mavlink_waypoint_t wp = cmd.convert(_guide->getCurrentIndex()); - mavlink_msg_waypoint_send(_channel, _cmdDestSysId, _cmdDestCompId, - wp.seq, wp.frame, wp.command, wp.current, wp.autocontinue, - wp.param1, wp.param2, wp.param3, wp.param4, wp.x, wp.y, - wp.z); + mavlink_waypoint_t wp = cmd.convert(_guide->getCurrentIndex()); + mavlink_msg_waypoint_send(_channel, _cmdDestSysId, _cmdDestCompId, + wp.seq, wp.frame, wp.command, wp.current, wp.autocontinue, + wp.param1, wp.param2, wp.param3, wp.param4, wp.x, wp.y, + wp.z); - // update last waypoint comm stamp - _cmdTimeLastSent = millis(); - break; - } + // update last waypoint comm stamp + _cmdTimeLastSent = millis(); + break; + } - case MAVLINK_MSG_ID_WAYPOINT_ACK: { - sendText(SEVERITY_LOW, PSTR("waypoint ack")); + case MAVLINK_MSG_ID_WAYPOINT_ACK: { + sendText(SEVERITY_LOW, PSTR("waypoint ack")); - // decode - mavlink_waypoint_ack_t packet; - mavlink_msg_waypoint_ack_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_ack_t packet; + mavlink_msg_waypoint_ack_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // check for error - //uint8_t type = packet.type; // ok (0), error(1) + // check for error + //uint8_t type = packet.type; // ok (0), error(1) - // turn off waypoint send - _sendingCmds = false; - break; - } + // turn off waypoint send + _sendingCmds = false; + break; + } - case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { - sendText(SEVERITY_LOW, PSTR("param request list")); + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { + sendText(SEVERITY_LOW, PSTR("param request list")); - // decode - mavlink_param_request_list_t packet; - mavlink_msg_param_request_list_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_param_request_list_t packet; + mavlink_msg_param_request_list_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // Start sending parameters - next call to ::update will kick the first one out + // Start sending parameters - next call to ::update will kick the first one out - _queuedParameter = AP_Var::first(); - _queuedParameterIndex = 0; - break; - } + _queuedParameter = AP_Var::first(); + _queuedParameterIndex = 0; + break; + } - case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: { - sendText(SEVERITY_LOW, PSTR("waypoint clear all")); + case MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL: { + sendText(SEVERITY_LOW, PSTR("waypoint clear all")); - // decode - mavlink_waypoint_clear_all_t packet; - mavlink_msg_waypoint_clear_all_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_clear_all_t packet; + mavlink_msg_waypoint_clear_all_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // clear all waypoints - uint8_t type = 0; // ok (0), error(1) - _guide->setNumberOfCommands(1); - _guide->setCurrentIndex(0); + // clear all waypoints + uint8_t type = 0; // ok (0), error(1) + _guide->setNumberOfCommands(1); + _guide->setCurrentIndex(0); - // send acknowledgement 3 times to makes sure it is received - for (int i = 0; i < 3; i++) - mavlink_msg_waypoint_ack_send(_channel, msg->sysid, - msg->compid, type); + // send acknowledgement 3 times to makes sure it is received + for (int i = 0; i < 3; i++) + mavlink_msg_waypoint_ack_send(_channel, msg->sysid, + msg->compid, type); - break; - } + break; + } - case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: { - sendText(SEVERITY_LOW, PSTR("waypoint set current")); + case MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT: { + sendText(SEVERITY_LOW, PSTR("waypoint set current")); - // decode - mavlink_waypoint_set_current_t packet; - mavlink_msg_waypoint_set_current_decode(msg, &packet); - Serial.print("Packet Sequence:"); - Serial.println(packet.seq); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_set_current_t packet; + mavlink_msg_waypoint_set_current_decode(msg, &packet); + Serial.print("Packet Sequence:"); + Serial.println(packet.seq); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // set current waypoint - Serial.print("Current Index:"); - Serial.println(_guide->getCurrentIndex()); - Serial.flush(); - _guide->setCurrentIndex(packet.seq); - mavlink_msg_waypoint_current_send(_channel, - _guide->getCurrentIndex()); - break; - } + // set current waypoint + Serial.print("Current Index:"); + Serial.println(_guide->getCurrentIndex()); + Serial.flush(); + _guide->setCurrentIndex(packet.seq); + mavlink_msg_waypoint_current_send(_channel, + _guide->getCurrentIndex()); + break; + } - case MAVLINK_MSG_ID_WAYPOINT_COUNT: { - sendText(SEVERITY_LOW, PSTR("waypoint count")); + case MAVLINK_MSG_ID_WAYPOINT_COUNT: { + sendText(SEVERITY_LOW, PSTR("waypoint count")); - // decode - mavlink_waypoint_count_t packet; - mavlink_msg_waypoint_count_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_count_t packet; + mavlink_msg_waypoint_count_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // start waypoint receiving - if (packet.count > _cmdMax) { - packet.count = _cmdMax; - } - _cmdNumberRequested = packet.count; - _cmdTimeLastReceived = millis(); - _receivingCmds = true; - _sendingCmds = false; - _cmdRequestIndex = 0; - break; - } + // start waypoint receiving + if (packet.count > _cmdMax) { + packet.count = _cmdMax; + } + _cmdNumberRequested = packet.count; + _cmdTimeLastReceived = millis(); + _receivingCmds = true; + _sendingCmds = false; + _cmdRequestIndex = 0; + break; + } - case MAVLINK_MSG_ID_WAYPOINT: { - sendText(SEVERITY_LOW, PSTR("waypoint")); + case MAVLINK_MSG_ID_WAYPOINT: { + sendText(SEVERITY_LOW, PSTR("waypoint")); - // Check if receiving waypiont - if (!_receivingCmds) { - //sendText(SEVERITY_HIGH, PSTR("not receiving commands")); - break; - } + // Check if receiving waypiont + if (!_receivingCmds) { + //sendText(SEVERITY_HIGH, PSTR("not receiving commands")); + break; + } - // decode - mavlink_waypoint_t packet; - mavlink_msg_waypoint_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_waypoint_t packet; + mavlink_msg_waypoint_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // check if this is the requested waypoint - if (packet.seq != _cmdRequestIndex) { - char warningMsg[50]; - sprintf(warningMsg, - "waypoint request out of sequence: (packet) %d / %d (ap)", - packet.seq, _cmdRequestIndex); - sendText(SEVERITY_HIGH, warningMsg); - break; - } + // check if this is the requested waypoint + if (packet.seq != _cmdRequestIndex) { + char warningMsg[50]; + sprintf(warningMsg, + "waypoint request out of sequence: (packet) %d / %d (ap)", + packet.seq, _cmdRequestIndex); + sendText(SEVERITY_HIGH, warningMsg); + break; + } - _hal->debug->printf_P(PSTR("received waypoint x: %f\ty: %f\tz: %f\n"), - packet.x, - packet.y, - packet.z); + _hal->debug->printf_P(PSTR("received waypoint x: %f\ty: %f\tz: %f\n"), + packet.x, + packet.y, + packet.z); - // store waypoint - AP_MavlinkCommand command(packet); - //sendText(SEVERITY_HIGH, PSTR("waypoint stored")); - _cmdRequestIndex++; - if (_cmdRequestIndex == _cmdNumberRequested) { - sendMessage(MAVLINK_MSG_ID_WAYPOINT_ACK); - _receivingCmds = false; - _guide->setNumberOfCommands(_cmdNumberRequested); - //sendText(SEVERITY_LOW, PSTR("waypoint ack sent")); - } else if (_cmdRequestIndex > _cmdNumberRequested) { - _receivingCmds = false; - } - _cmdTimeLastReceived = millis(); - break; - } + // store waypoint + AP_MavlinkCommand command(packet); + //sendText(SEVERITY_HIGH, PSTR("waypoint stored")); + _cmdRequestIndex++; + if (_cmdRequestIndex == _cmdNumberRequested) { + sendMessage(MAVLINK_MSG_ID_WAYPOINT_ACK); + _receivingCmds = false; + _guide->setNumberOfCommands(_cmdNumberRequested); + //sendText(SEVERITY_LOW, PSTR("waypoint ack sent")); + } else if (_cmdRequestIndex > _cmdNumberRequested) { + _receivingCmds = false; + } + _cmdTimeLastReceived = millis(); + break; + } - case MAVLINK_MSG_ID_PARAM_SET: { - sendText(SEVERITY_LOW, PSTR("param set")); - AP_Var *vp; - AP_Meta_class::Type_id var_type; + case MAVLINK_MSG_ID_PARAM_SET: { + sendText(SEVERITY_LOW, PSTR("param set")); + AP_Var *vp; + AP_Meta_class::Type_id var_type; - // decode - mavlink_param_set_t packet; - mavlink_msg_param_set_decode(msg, &packet); - if (_checkTarget(packet.target_system, packet.target_component)) - break; + // decode + mavlink_param_set_t packet; + mavlink_msg_param_set_decode(msg, &packet); + if (_checkTarget(packet.target_system, packet.target_component)) + break; - // set parameter + // set parameter - char key[_paramNameLengthMax + 1]; - strncpy(key, (char *) packet.param_id, _paramNameLengthMax); - key[_paramNameLengthMax] = 0; + char key[_paramNameLengthMax + 1]; + strncpy(key, (char *) packet.param_id, _paramNameLengthMax); + key[_paramNameLengthMax] = 0; - // find the requested parameter - vp = AP_Var::find(key); - if ((NULL != vp) && // exists - !isnan(packet.param_value) && // not nan - !isinf(packet.param_value)) { // not inf + // find the requested parameter + vp = AP_Var::find(key); + if ((NULL != vp) && // exists + !isnan(packet.param_value) && // not nan + !isinf(packet.param_value)) { // not inf - // add a small amount before casting parameter values - // from float to integer to avoid truncating to the - // next lower integer value. - const float rounding_addition = 0.01; + // add a small amount before casting parameter values + // from float to integer to avoid truncating to the + // next lower integer value. + const float rounding_addition = 0.01; - // fetch the variable type ID - var_type = vp->meta_type_id(); + // fetch the variable type ID + var_type = vp->meta_type_id(); - // handle variables with standard type IDs - if (var_type == AP_Var::k_typeid_float) { - ((AP_Float *) vp)->set_and_save(packet.param_value); + // handle variables with standard type IDs + if (var_type == AP_Var::k_typeid_float) { + ((AP_Float *) vp)->set_and_save(packet.param_value); - } else if (var_type == AP_Var::k_typeid_float16) { - ((AP_Float16 *) vp)->set_and_save(packet.param_value); + } else if (var_type == AP_Var::k_typeid_float16) { + ((AP_Float16 *) vp)->set_and_save(packet.param_value); - } else if (var_type == AP_Var::k_typeid_int32) { - ((AP_Int32 *) vp)->set_and_save( - packet.param_value + rounding_addition); + } else if (var_type == AP_Var::k_typeid_int32) { + ((AP_Int32 *) vp)->set_and_save( + packet.param_value + rounding_addition); - } else if (var_type == AP_Var::k_typeid_int16) { - ((AP_Int16 *) vp)->set_and_save( - packet.param_value + rounding_addition); + } else if (var_type == AP_Var::k_typeid_int16) { + ((AP_Int16 *) vp)->set_and_save( + packet.param_value + rounding_addition); - } else if (var_type == AP_Var::k_typeid_int8) { - ((AP_Int8 *) vp)->set_and_save( - packet.param_value + rounding_addition); - } else { - // we don't support mavlink set on this parameter - break; - } + } else if (var_type == AP_Var::k_typeid_int8) { + ((AP_Int8 *) vp)->set_and_save( + packet.param_value + rounding_addition); + } else { + // we don't support mavlink set on this parameter + break; + } - // Report back the new value if we accepted the change - // we send the value we actually set, which could be - // different from the value sent, in case someone sent - // a fractional value to an integer type - mavlink_msg_param_value_send(_channel, (int8_t *) key, - vp->cast_to_float(), _countParameters(), -1); // XXX we don't actually know what its index is... - } + // Report back the new value if we accepted the change + // we send the value we actually set, which could be + // different from the value sent, in case someone sent + // a fractional value to an integer type + mavlink_msg_param_value_send(_channel, (int8_t *) key, + vp->cast_to_float(), _countParameters(), -1); // XXX we don't actually know what its index is... + } - break; - } // end case + break; + } // end case - } + } } uint16_t MavlinkComm::_countParameters() { - // if we haven't cached the parameter count yet... - if (0 == _parameterCount) { - AP_Var *vp; + // if we haven't cached the parameter count yet... + if (0 == _parameterCount) { + AP_Var *vp; - vp = AP_Var::first(); - do { - // if a parameter responds to cast_to_float then we are going to be able to report it - if (!isnan(vp->cast_to_float())) { - _parameterCount++; - } - } while (NULL != (vp = vp->next())); - } - return _parameterCount; + vp = AP_Var::first(); + do { + // if a parameter responds to cast_to_float then we are going to be able to report it + if (!isnan(vp->cast_to_float())) { + _parameterCount++; + } + } while (NULL != (vp = vp->next())); + } + return _parameterCount; } AP_Var * _findParameter(uint16_t index) { - AP_Var *vp; + AP_Var *vp; - vp = AP_Var::first(); - while (NULL != vp) { + vp = AP_Var::first(); + while (NULL != vp) { - // if the parameter is reportable - if (!(isnan(vp->cast_to_float()))) { - // if we have counted down to the index we want - if (0 == index) { - // return the parameter - return vp; - } - // count off this parameter, as it is reportable but not - // the one we want - index--; - } - // and move to the next parameter - vp = vp->next(); - } - return NULL; + // if the parameter is reportable + if (!(isnan(vp->cast_to_float()))) { + // if we have counted down to the index we want + if (0 == index) { + // return the parameter + return vp; + } + // count off this parameter, as it is reportable but not + // the one we want + index--; + } + // and move to the next parameter + vp = vp->next(); + } + return NULL; } // check the target uint8_t MavlinkComm::_checkTarget(uint8_t sysid, uint8_t compid) { - /* - char msg[50]; - sprintf(msg, "target = %d / %d\tcomp = %d / %d", sysid, - mavlink_system.sysid, compid, mavlink_system.compid); - sendText(SEVERITY_LOW, msg); - */ - if (sysid != mavlink_system.sysid) { - //sendText(SEVERITY_LOW, PSTR("system id mismatch")); - return 1; + /* + char msg[50]; + sprintf(msg, "target = %d / %d\tcomp = %d / %d", sysid, + mavlink_system.sysid, compid, mavlink_system.compid); + sendText(SEVERITY_LOW, msg); + */ + if (sysid != mavlink_system.sysid) { + //sendText(SEVERITY_LOW, PSTR("system id mismatch")); + return 1; - } else if (compid != mavlink_system.compid) { - //sendText(SEVERITY_LOW, PSTR("component id mismatch")); - return 0; // XXX currently not receiving correct compid from gcs + } else if (compid != mavlink_system.compid) { + //sendText(SEVERITY_LOW, PSTR("component id mismatch")); + return 0; // XXX currently not receiving correct compid from gcs - } else { - return 0; // no error - } + } else { + return 0; // no error + } } } // apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_CommLink.h b/libraries/APO/AP_CommLink.h index be473cde9a..76b4c5e772 100644 --- a/libraries/APO/AP_CommLink.h +++ b/libraries/APO/AP_CommLink.h @@ -22,7 +22,7 @@ #include #include "../AP_Common/AP_Common.h" #include "../AP_Common/AP_Vector.h" -#include "AP_MavlinkCommand.h" +#include "../GCS_MAVLink/GCS_MAVLink.h" class FastSerial; @@ -34,7 +34,7 @@ class AP_Guide; class AP_HardwareAbstractionLayer; enum { - SEVERITY_LOW, SEVERITY_MED, SEVERITY_HIGH + SEVERITY_LOW, SEVERITY_MED, SEVERITY_HIGH }; // forward declarations @@ -45,83 +45,83 @@ enum { class AP_CommLink { public: - AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal); - virtual void send() = 0; - virtual void receive() = 0; - virtual void sendMessage(uint8_t id, uint32_t param = 0) = 0; - virtual void sendText(uint8_t severity, const char *str) = 0; - virtual void sendText(uint8_t severity, const prog_char_t *str) = 0; - virtual void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) = 0; - virtual void sendParameters() = 0; - virtual void requestCmds() = 0; + AP_CommLink(FastSerial * link, AP_Navigator * navigator, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal); + virtual void send() = 0; + virtual void receive() = 0; + virtual void sendMessage(uint8_t id, uint32_t param = 0) = 0; + virtual void sendText(uint8_t severity, const char *str) = 0; + virtual void sendText(uint8_t severity, const prog_char_t *str) = 0; + virtual void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2) = 0; + virtual void sendParameters() = 0; + virtual void requestCmds() = 0; protected: - FastSerial * _link; - AP_Navigator * _navigator; - AP_Guide * _guide; - AP_Controller * _controller; - AP_HardwareAbstractionLayer * _hal; + FastSerial * _link; + AP_Navigator * _navigator; + AP_Guide * _guide; + AP_Controller * _controller; + AP_HardwareAbstractionLayer * _hal; }; class MavlinkComm: public AP_CommLink { public: - MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide, - AP_Controller * controller, AP_HardwareAbstractionLayer * hal); + MavlinkComm(FastSerial * link, AP_Navigator * nav, AP_Guide * guide, + AP_Controller * controller, AP_HardwareAbstractionLayer * hal); - virtual void send(); - void sendMessage(uint8_t id, uint32_t param = 0); - virtual void receive(); - void sendText(uint8_t severity, const char *str); - void sendText(uint8_t severity, const prog_char_t *str); - void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2); + virtual void send(); + void sendMessage(uint8_t id, uint32_t param = 0); + virtual void receive(); + void sendText(uint8_t severity, const char *str); + void sendText(uint8_t severity, const prog_char_t *str); + void acknowledge(uint8_t id, uint8_t sum1, uint8_t sum2); - /** - * sends parameters one at a time - */ - void sendParameters(); + /** + * sends parameters one at a time + */ + void sendParameters(); - /** - * request commands one at a time - */ - void requestCmds(); + /** + * request commands one at a time + */ + void requestCmds(); private: - // options - bool _useRelativeAlt; + // options + bool _useRelativeAlt; - // commands - bool _sendingCmds; - bool _receivingCmds; - uint16_t _cmdTimeLastSent; - uint16_t _cmdTimeLastReceived; - uint16_t _cmdDestSysId; - uint16_t _cmdDestCompId; - uint16_t _cmdRequestIndex; - uint16_t _cmdNumberRequested; - uint16_t _cmdMax; - Vector _cmdList; + // commands + bool _sendingCmds; + bool _receivingCmds; + uint16_t _cmdTimeLastSent; + uint16_t _cmdTimeLastReceived; + uint16_t _cmdDestSysId; + uint16_t _cmdDestCompId; + uint16_t _cmdRequestIndex; + uint16_t _cmdNumberRequested; + uint16_t _cmdMax; + Vector _cmdList; - // parameters - static uint8_t _paramNameLengthMax; - uint16_t _parameterCount; - AP_Var * _queuedParameter; - uint16_t _queuedParameterIndex; + // parameters + static uint8_t _paramNameLengthMax; + uint16_t _parameterCount; + AP_Var * _queuedParameter; + uint16_t _queuedParameterIndex; - // channel - mavlink_channel_t _channel; - uint16_t _packetDrops; - static uint8_t _nChannels; + // channel + mavlink_channel_t _channel; + uint16_t _packetDrops; + static uint8_t _nChannels; - void _handleMessage(mavlink_message_t * msg); + void _handleMessage(mavlink_message_t * msg); - uint16_t _countParameters(); + uint16_t _countParameters(); - AP_Var * _findParameter(uint16_t index); + AP_Var * _findParameter(uint16_t index); - // check the target - uint8_t _checkTarget(uint8_t sysid, uint8_t compid); + // check the target + uint8_t _checkTarget(uint8_t sysid, uint8_t compid); }; diff --git a/libraries/APO/AP_Controller.cpp b/libraries/APO/AP_Controller.cpp index 443fe2afbb..933727a3d5 100644 --- a/libraries/APO/AP_Controller.cpp +++ b/libraries/APO/AP_Controller.cpp @@ -6,28 +6,118 @@ */ #include "AP_Controller.h" +#include "../FastSerial/FastSerial.h" +#include "AP_ArmingMechanism.h" +#include "AP_BatteryMonitor.h" #include "AP_HardwareAbstractionLayer.h" #include "../AP_Common/include/menu.h" #include "AP_RcChannel.h" +#include "../GCS_MAVLink/include/mavlink_types.h" +#include "constants.h" +#include "AP_CommLink.h" namespace apo { AP_Controller::AP_Controller(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal) : - _nav(nav), _guide(guide), _hal(hal) { - setAllRadioChannelsToNeutral(); + AP_HardwareAbstractionLayer * hal, AP_ArmingMechanism * armingMechanism, + const uint8_t chMode, const uint16_t key, const prog_char_t * name) : + _nav(nav), _guide(guide), _hal(hal), _armingMechanism(armingMechanism), + _group(key, name ? : PSTR("CNTRL_")), + _chMode(chMode), + _mode(&_group, 1, MAV_MODE_LOCKED, PSTR("MODE")) { + setAllRadioChannelsToNeutral(); } void AP_Controller::setAllRadioChannelsToNeutral() { - for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { - _hal->rc[i]->setPosition(0.0); - } + for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { + _hal->rc[i]->setPosition(0.0); + } } void AP_Controller::setAllRadioChannelsManually() { - for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { - _hal->rc[i]->setUsingRadio(); - } + for (uint8_t i = 0; i < _hal->rc.getSize(); i++) { + _hal->rc[i]->setUsingRadio(); + } } +void AP_Controller::update(const float dt) { + if (_armingMechanism) _armingMechanism->update(dt); + + // determine flight mode + // + // check for heartbeat from gcs, if not found go to failsafe + if (_hal->heartBeatLost()) { + _mode = MAV_MODE_FAILSAFE; + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("configure gcs to send heartbeat")); + // if battery less than 5%, go to failsafe + } else if (_hal->batteryMonitor && _hal->batteryMonitor->getPercentage() < 5) { + _mode = MAV_MODE_FAILSAFE; + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("recharge battery")); + // manual/auto switch + } else { + // if all emergencies cleared, fall back to standby + if (_hal->getState()==MAV_STATE_EMERGENCY) _hal->setState(MAV_STATE_STANDBY); + if (_hal->rc[_chMode]->getRadioPosition() > 0) _mode = MAV_MODE_MANUAL; + else _mode = MAV_MODE_AUTO; + } + + // handle flight modes + switch(_mode) { + + case MAV_MODE_LOCKED: { + _hal->setState(MAV_STATE_STANDBY); + break; + } + + case MAV_MODE_FAILSAFE: { + _hal->setState(MAV_STATE_EMERGENCY); + break; + } + + case MAV_MODE_MANUAL: { + manualLoop(dt); + break; + } + + case MAV_MODE_AUTO: { + autoLoop(dt); + break; + } + + default: { + _hal->gcs->sendText(SEVERITY_HIGH, PSTR("unknown mode")); + _hal->setState(MAV_STATE_EMERGENCY); + } + } + + // this sends commands to motors + setMotors(); } + +void AP_Controller::setMotors() { + switch (_hal->getState()) { + + case MAV_STATE_ACTIVE: { + digitalWrite(_hal->aLedPin, HIGH); + setMotorsActive(); + } + case MAV_STATE_EMERGENCY: { + digitalWrite(_hal->aLedPin, LOW); + setMotorsEmergency(); + break; + } + case MAV_STATE_STANDBY: { + digitalWrite(_hal->aLedPin,LOW); + setMotorsStandby(); + break; + } + default: { + setMotorsStandby(); + } + + } +} + + +} // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Controller.h b/libraries/APO/AP_Controller.h index 4cfc57609d..4c5fe8a260 100644 --- a/libraries/APO/AP_Controller.h +++ b/libraries/APO/AP_Controller.h @@ -22,6 +22,8 @@ #include #include "../GCS_MAVLink/GCS_MAVLink.h" #include +#include "../AP_Common/AP_Var.h" +#include "AP_Var_keys.h" class AP_Var_group; @@ -31,269 +33,293 @@ class AP_HardwareAbstractionLayer; class AP_Guide; class AP_Navigator; class Menu; +class AP_ArmingMechanism; /// Controller class class AP_Controller { public: - AP_Controller(AP_Navigator * nav, AP_Guide * guide, - AP_HardwareAbstractionLayer * hal); - virtual void update(const float & dt) = 0; - virtual MAV_MODE getMode() = 0; - void setAllRadioChannelsToNeutral(); - void setAllRadioChannelsManually(); - + AP_Controller(AP_Navigator * nav, AP_Guide * guide, + AP_HardwareAbstractionLayer * hal, + AP_ArmingMechanism * armingMechanism, + const uint8_t _chMode, + const uint16_t key = k_cntrl, + const prog_char_t * name = NULL); + virtual void update(const float dt); + void setAllRadioChannelsToNeutral(); + void setAllRadioChannelsManually(); + virtual void setMotors(); + virtual void setMotorsActive() = 0; + virtual void setMotorsEmergency() { + setAllRadioChannelsToNeutral(); + }; + virtual void setMotorsStandby() { + setAllRadioChannelsToNeutral(); + }; + virtual void manualLoop(const float dt) { + setAllRadioChannelsToNeutral(); + }; + virtual void autoLoop(const float dt) { + setAllRadioChannelsToNeutral(); + }; + AP_Uint8 getMode() { + return _mode; + } protected: - AP_Navigator * _nav; - AP_Guide * _guide; - AP_HardwareAbstractionLayer * _hal; + AP_Navigator * _nav; + AP_Guide * _guide; + AP_HardwareAbstractionLayer * _hal; + AP_ArmingMechanism * _armingMechanism; + uint8_t _chMode; + AP_Var_group _group; + AP_Uint8 _mode; }; class AP_ControllerBlock { public: - AP_ControllerBlock(AP_Var_group * group, uint8_t groupStart, - uint8_t groupLength) : - _group(group), _groupStart(groupStart), - _groupEnd(groupStart + groupLength) { - } - uint8_t getGroupEnd() { - return _groupEnd; - } + AP_ControllerBlock(AP_Var_group * group, uint8_t groupStart, + uint8_t groupLength) : + _group(group), _groupStart(groupStart), + _groupEnd(groupStart + groupLength) { + } + uint8_t getGroupEnd() { + return _groupEnd; + } protected: - AP_Var_group * _group; /// helps with parameter management - uint8_t _groupStart; - uint8_t _groupEnd; + AP_Var_group * _group; /// helps with parameter management + uint8_t _groupStart; + uint8_t _groupEnd; }; class BlockLowPass: public AP_ControllerBlock { public: - BlockLowPass(AP_Var_group * group, uint8_t groupStart, float fCut, - const prog_char_t * fCutLabel = NULL) : - AP_ControllerBlock(group, groupStart, 1), - _fCut(group, groupStart, fCut, fCutLabel ? : PSTR("fCut")), - _y(0) { - } - float update(const float & input, const float & dt) { - float RC = 1 / (2 * M_PI * _fCut); // low pass filter - _y = _y + (input - _y) * (dt / (dt + RC)); - return _y; - } + BlockLowPass(AP_Var_group * group, uint8_t groupStart, float fCut, + const prog_char_t * fCutLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _fCut(group, groupStart, fCut, fCutLabel ? : PSTR("fCut")), + _y(0) { + } + float update(const float & input, const float & dt) { + float RC = 1 / (2 * M_PI * _fCut); // low pass filter + _y = _y + (input - _y) * (dt / (dt + RC)); + return _y; + } protected: - AP_Float _fCut; - float _y; + AP_Float _fCut; + float _y; }; class BlockSaturation: public AP_ControllerBlock { public: - BlockSaturation(AP_Var_group * group, uint8_t groupStart, float yMax, - const prog_char_t * yMaxLabel = NULL) : - AP_ControllerBlock(group, groupStart, 1), - _yMax(group, groupStart, yMax, yMaxLabel ? : PSTR("yMax")) { - } - float update(const float & input) { + BlockSaturation(AP_Var_group * group, uint8_t groupStart, float yMax, + const prog_char_t * yMaxLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _yMax(group, groupStart, yMax, yMaxLabel ? : PSTR("yMax")) { + } + float update(const float & input) { - // pid sum - float y = input; + // pid sum + float y = input; - // saturation - if (y > _yMax) - y = _yMax; - if (y < -_yMax) - y = -_yMax; - return y; - } + // saturation + if (y > _yMax) + y = _yMax; + if (y < -_yMax) + y = -_yMax; + return y; + } protected: - AP_Float _yMax; /// output saturation + AP_Float _yMax; /// output saturation }; class BlockDerivative { public: - BlockDerivative() : - _lastInput(0), firstRun(true) { - } - float update(const float & input, const float & dt) { - float derivative = (input - _lastInput) / dt; - _lastInput = input; - if (firstRun) { - firstRun = false; - return 0; - } else - return derivative; - } + BlockDerivative() : + _lastInput(0), firstRun(true) { + } + float update(const float & input, const float & dt) { + float derivative = (input - _lastInput) / dt; + _lastInput = input; + if (firstRun) { + firstRun = false; + return 0; + } else + return derivative; + } protected: - float _lastInput; /// last input - bool firstRun; + float _lastInput; /// last input + bool firstRun; }; class BlockIntegral { public: - BlockIntegral() : - _i(0) { - } - float update(const float & input, const float & dt) { - _i += input * dt; - return _i; - } + BlockIntegral() : + _i(0) { + } + float update(const float & input, const float & dt) { + _i += input * dt; + return _i; + } protected: - float _i; /// integral + float _i; /// integral }; class BlockP: public AP_ControllerBlock { public: - BlockP(AP_Var_group * group, uint8_t groupStart, float kP, - const prog_char_t * kPLabel = NULL) : - AP_ControllerBlock(group, groupStart, 1), - _kP(group, groupStart, kP, kPLabel ? : PSTR("p")) { - } + BlockP(AP_Var_group * group, uint8_t groupStart, float kP, + const prog_char_t * kPLabel = NULL) : + AP_ControllerBlock(group, groupStart, 1), + _kP(group, groupStart, kP, kPLabel ? : PSTR("p")) { + } - float update(const float & input) { - return _kP * input; - } + float update(const float & input) { + return _kP * input; + } protected: - AP_Float _kP; /// proportional gain + AP_Float _kP; /// proportional gain }; class BlockI: public AP_ControllerBlock { public: - BlockI(AP_Var_group * group, uint8_t groupStart, float kI, float iMax, - const prog_char_t * kILabel = NULL, - const prog_char_t * iMaxLabel = NULL) : - AP_ControllerBlock(group, groupStart, 2), - _kI(group, groupStart, kI, kILabel ? : PSTR("i")), - _blockSaturation(group, groupStart + 1, iMax, iMaxLabel ? : PSTR("iMax")), - _eI(0) { - } + BlockI(AP_Var_group * group, uint8_t groupStart, float kI, float iMax, + const prog_char_t * kILabel = NULL, + const prog_char_t * iMaxLabel = NULL) : + AP_ControllerBlock(group, groupStart, 2), + _kI(group, groupStart, kI, kILabel ? : PSTR("i")), + _blockSaturation(group, groupStart + 1, iMax, iMaxLabel ? : PSTR("iMax")), + _eI(0) { + } - float update(const float & input, const float & dt) { - // integral - _eI += input * dt; - _eI = _blockSaturation.update(_eI); - return _kI * _eI; - } + float update(const float & input, const float & dt) { + // integral + _eI += input * dt; + _eI = _blockSaturation.update(_eI); + return _kI * _eI; + } protected: - AP_Float _kI; /// integral gain - BlockSaturation _blockSaturation; /// integrator saturation - float _eI; /// integral of input + AP_Float _kI; /// integral gain + BlockSaturation _blockSaturation; /// integrator saturation + float _eI; /// integral of input }; class BlockD: public AP_ControllerBlock { public: - BlockD(AP_Var_group * group, uint8_t groupStart, float kD, uint8_t dFCut, - const prog_char_t * kDLabel = NULL, - const prog_char_t * dFCutLabel = NULL) : - AP_ControllerBlock(group, groupStart, 2), - _blockLowPass(group, groupStart, dFCut, - dFCutLabel ? : PSTR("dFCut")), - _kD(group, _blockLowPass.getGroupEnd(), kD, - kDLabel ? : PSTR("d")), _eP(0) { - } - float update(const float & input, const float & dt) { - // derivative with low pass - float _eD = _blockLowPass.update((_eP - input) / dt, dt); - // proportional, note must come after derivative - // because derivatve uses _eP as previous value - _eP = input; - return _kD * _eD; - } + BlockD(AP_Var_group * group, uint8_t groupStart, float kD, uint8_t dFCut, + const prog_char_t * kDLabel = NULL, + const prog_char_t * dFCutLabel = NULL) : + AP_ControllerBlock(group, groupStart, 2), + _blockLowPass(group, groupStart, dFCut, + dFCutLabel ? : PSTR("dFCut")), + _kD(group, _blockLowPass.getGroupEnd(), kD, + kDLabel ? : PSTR("d")), _eP(0) { + } + float update(const float & input, const float & dt) { + // derivative with low pass + float _eD = _blockLowPass.update((_eP - input) / dt, dt); + // proportional, note must come after derivative + // because derivatve uses _eP as previous value + _eP = input; + return _kD * _eD; + } protected: - BlockLowPass _blockLowPass; - AP_Float _kD; /// derivative gain - float _eP; /// input + BlockLowPass _blockLowPass; + AP_Float _kD; /// derivative gain + float _eP; /// input }; class BlockPID: public AP_ControllerBlock { public: - BlockPID(AP_Var_group * group, uint8_t groupStart, float kP, float kI, - float kD, float iMax, float yMax, uint8_t dFcut) : - AP_ControllerBlock(group, groupStart, 6), - _blockP(group, groupStart, kP), - _blockI(group, _blockP.getGroupEnd(), kI, iMax), - _blockD(group, _blockI.getGroupEnd(), kD, dFcut), - _blockSaturation(group, _blockD.getGroupEnd(), yMax) { - } + BlockPID(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, uint8_t dFcut) : + AP_ControllerBlock(group, groupStart, 6), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockD(group, _blockI.getGroupEnd(), kD, dFcut), + _blockSaturation(group, _blockD.getGroupEnd(), yMax) { + } - float update(const float & input, const float & dt) { - return _blockSaturation.update( - _blockP.update(input) + _blockI.update(input, dt) - + _blockD.update(input, dt)); - } + float update(const float & input, const float & dt) { + return _blockSaturation.update( + _blockP.update(input) + _blockI.update(input, dt) + + _blockD.update(input, dt)); + } protected: - BlockP _blockP; - BlockI _blockI; - BlockD _blockD; - BlockSaturation _blockSaturation; + BlockP _blockP; + BlockI _blockI; + BlockD _blockD; + BlockSaturation _blockSaturation; }; class BlockPI: public AP_ControllerBlock { public: - BlockPI(AP_Var_group * group, uint8_t groupStart, float kP, float kI, - float iMax, float yMax) : - AP_ControllerBlock(group, groupStart, 4), - _blockP(group, groupStart, kP), - _blockI(group, _blockP.getGroupEnd(), kI, iMax), - _blockSaturation(group, _blockI.getGroupEnd(), yMax) { - } + BlockPI(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float iMax, float yMax) : + AP_ControllerBlock(group, groupStart, 4), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockSaturation(group, _blockI.getGroupEnd(), yMax) { + } - float update(const float & input, const float & dt) { + float update(const float & input, const float & dt) { - float y = _blockP.update(input) + _blockI.update(input, dt); - return _blockSaturation.update(y); - } + float y = _blockP.update(input) + _blockI.update(input, dt); + return _blockSaturation.update(y); + } protected: - BlockP _blockP; - BlockI _blockI; - BlockSaturation _blockSaturation; + BlockP _blockP; + BlockI _blockI; + BlockSaturation _blockSaturation; }; class BlockPD: public AP_ControllerBlock { public: - BlockPD(AP_Var_group * group, uint8_t groupStart, float kP, float kI, - float kD, float iMax, float yMax, uint8_t dFcut) : - AP_ControllerBlock(group, groupStart, 4), - _blockP(group, groupStart, kP), - _blockD(group, _blockP.getGroupEnd(), kD, dFcut), - _blockSaturation(group, _blockD.getGroupEnd(), yMax) { - } + BlockPD(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, uint8_t dFcut) : + AP_ControllerBlock(group, groupStart, 4), + _blockP(group, groupStart, kP), + _blockD(group, _blockP.getGroupEnd(), kD, dFcut), + _blockSaturation(group, _blockD.getGroupEnd(), yMax) { + } - float update(const float & input, const float & dt) { + float update(const float & input, const float & dt) { - float y = _blockP.update(input) + _blockD.update(input, dt); - return _blockSaturation.update(y); - } + float y = _blockP.update(input) + _blockD.update(input, dt); + return _blockSaturation.update(y); + } protected: - BlockP _blockP; - BlockD _blockD; - BlockSaturation _blockSaturation; + BlockP _blockP; + BlockD _blockD; + BlockSaturation _blockSaturation; }; /// PID with derivative feedback (ignores reference derivative) class BlockPIDDfb: public AP_ControllerBlock { public: - BlockPIDDfb(AP_Var_group * group, uint8_t groupStart, float kP, float kI, - float kD, float iMax, float yMax, float dFCut, - const prog_char_t * dFCutLabel = NULL, - const prog_char_t * dLabel = NULL) : - AP_ControllerBlock(group, groupStart, 5), - _blockP(group, groupStart, kP), - _blockI(group, _blockP.getGroupEnd(), kI, iMax), - _blockSaturation(group, _blockI.getGroupEnd(), yMax), - _blockLowPass(group, _blockSaturation.getGroupEnd(), dFCut, - dFCutLabel ? : PSTR("dFCut")), - _kD(group, _blockLowPass.getGroupEnd(), kD, dLabel ? : PSTR("d")) - { - } - float update(const float & input, const float & derivative, - const float & dt) { - - float y = _blockP.update(input) + _blockI.update(input, dt) - _kD - * _blockLowPass.update(derivative,dt); - return _blockSaturation.update(y); - } + BlockPIDDfb(AP_Var_group * group, uint8_t groupStart, float kP, float kI, + float kD, float iMax, float yMax, float dFCut, + const prog_char_t * dFCutLabel = NULL, + const prog_char_t * dLabel = NULL) : + AP_ControllerBlock(group, groupStart, 5), + _blockP(group, groupStart, kP), + _blockI(group, _blockP.getGroupEnd(), kI, iMax), + _blockSaturation(group, _blockI.getGroupEnd(), yMax), + _blockLowPass(group, _blockSaturation.getGroupEnd(), dFCut, + dFCutLabel ? : PSTR("dFCut")), + _kD(group, _blockLowPass.getGroupEnd(), kD, dLabel ? : PSTR("d")) + { + } + float update(const float & input, const float & derivative, + const float & dt) { + + float y = _blockP.update(input) + _blockI.update(input, dt) - _kD + * _blockLowPass.update(derivative,dt); + return _blockSaturation.update(y); + } protected: - BlockP _blockP; - BlockI _blockI; - BlockSaturation _blockSaturation; - BlockLowPass _blockLowPass; - AP_Float _kD; /// derivative gain + BlockP _blockP; + BlockI _blockI; + BlockSaturation _blockSaturation; + BlockLowPass _blockLowPass; + AP_Float _kD; /// derivative gain }; } // apo diff --git a/libraries/APO/AP_Guide.cpp b/libraries/APO/AP_Guide.cpp index def30d834c..e354424756 100644 --- a/libraries/APO/AP_Guide.cpp +++ b/libraries/APO/AP_Guide.cpp @@ -15,65 +15,75 @@ namespace apo { AP_Guide::AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal) : - _navigator(navigator), _hal(hal), _command(AP_MavlinkCommand::home), - _previousCommand(AP_MavlinkCommand::home), - _headingCommand(0), _airSpeedCommand(0), - _groundSpeedCommand(0), _altitudeCommand(0), _pNCmd(0), - _pECmd(0), _pDCmd(0), _mode(MAV_NAV_LOST), - _numberOfCommands(1), _cmdIndex(0), _nextCommandCalls(0), - _nextCommandTimer(0) { + _navigator(navigator), _hal(hal), _command(AP_MavlinkCommand::home), + _previousCommand(AP_MavlinkCommand::home), + _headingCommand(0), _airSpeedCommand(0), + _groundSpeedCommand(0), _altitudeCommand(0), _pNCmd(0), + _pECmd(0), _pDCmd(0), _mode(MAV_NAV_LOST), + _numberOfCommands(1), _cmdIndex(0), _nextCommandCalls(0), + _nextCommandTimer(0) { } -void AP_Guide::setCurrentIndex(uint8_t val){ - _cmdIndex.set_and_save(val); - _command = AP_MavlinkCommand(getCurrentIndex()); - _previousCommand = AP_MavlinkCommand(getPreviousIndex()); - _hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT); +void AP_Guide::setCurrentIndex(uint8_t val) { + _cmdIndex.set_and_save(val); + _command = AP_MavlinkCommand(getCurrentIndex()); + _previousCommand = AP_MavlinkCommand(getPreviousIndex()); + _hal->gcs->sendMessage(MAVLINK_MSG_ID_WAYPOINT_CURRENT); +} + +float AP_Guide::getHeadingError() { + float headingError = getHeadingCommand() + - _navigator->getYaw(); + if (headingError > 180 * deg2Rad) + headingError -= 360 * deg2Rad; + if (headingError < -180 * deg2Rad) + headingError += 360 * deg2Rad; + return headingError; } MavlinkGuide::MavlinkGuide(AP_Navigator * navigator, - AP_HardwareAbstractionLayer * hal) : - AP_Guide(navigator, hal), _rangeFinderFront(), _rangeFinderBack(), - _rangeFinderLeft(), _rangeFinderRight(), - _group(k_guide, PSTR("guide_")), - _velocityCommand(&_group, 1, 1, PSTR("velCmd")), - _crossTrackGain(&_group, 2, 1, PSTR("xt")), - _crossTrackLim(&_group, 3, 90, PSTR("xtLim")) { + AP_HardwareAbstractionLayer * hal, float velCmd, float xt, float xtLim) : + AP_Guide(navigator, hal), _rangeFinderFront(), _rangeFinderBack(), + _rangeFinderLeft(), _rangeFinderRight(), + _group(k_guide, PSTR("guide_")), + _velocityCommand(&_group, 1, velCmd, PSTR("velCmd")), + _crossTrackGain(&_group, 2, xt, PSTR("xt")), + _crossTrackLim(&_group, 3, xtLim, PSTR("xtLim")) { - for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) { - RangeFinder * rF = _hal->rangeFinders[i]; - if (rF == NULL) - continue; - if (rF->orientation_x == 1 && rF->orientation_y == 0 - && rF->orientation_z == 0) - _rangeFinderFront = rF; - else if (rF->orientation_x == -1 && rF->orientation_y == 0 - && rF->orientation_z == 0) - _rangeFinderBack = rF; - else if (rF->orientation_x == 0 && rF->orientation_y == 1 - && rF->orientation_z == 0) - _rangeFinderRight = rF; - else if (rF->orientation_x == 0 && rF->orientation_y == -1 - && rF->orientation_z == 0) - _rangeFinderLeft = rF; + for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) { + RangeFinder * rF = _hal->rangeFinders[i]; + if (rF == NULL) + continue; + if (rF->orientation_x == 1 && rF->orientation_y == 0 + && rF->orientation_z == 0) + _rangeFinderFront = rF; + else if (rF->orientation_x == -1 && rF->orientation_y == 0 + && rF->orientation_z == 0) + _rangeFinderBack = rF; + else if (rF->orientation_x == 0 && rF->orientation_y == 1 + && rF->orientation_z == 0) + _rangeFinderRight = rF; + else if (rF->orientation_x == 0 && rF->orientation_y == -1 + && rF->orientation_z == 0) + _rangeFinderLeft = rF; - } + } } void MavlinkGuide::update() { - // process mavlink commands - handleCommand(); + // process mavlink commands + handleCommand(); - // obstacle avoidance overrides - // stop if your going to drive into something in front of you - for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) - _hal->rangeFinders[i]->read(); - float frontDistance = _rangeFinderFront->distance / 200.0; //convert for other adc - if (_rangeFinderFront && frontDistance < 2) { - _mode = MAV_NAV_VECTOR; + // obstacle avoidance overrides + // stop if your going to drive into something in front of you + for (uint8_t i = 0; i < _hal->rangeFinders.getSize(); i++) + _hal->rangeFinders[i]->read(); + float frontDistance = _rangeFinderFront->distance / 200.0; //convert for other adc + if (_rangeFinderFront && frontDistance < 2) { + _mode = MAV_NAV_VECTOR; - //airSpeedCommand = 0; - //groundSpeedCommand = 0; + //airSpeedCommand = 0; + //groundSpeedCommand = 0; // _headingCommand -= 45 * deg2Rad; // _hal->debug->print("Obstacle Distance (m): "); // _hal->debug->println(frontDistance); @@ -82,120 +92,120 @@ void MavlinkGuide::update() { // _hal->debug->printf_P( // PSTR("Front Distance, %f\n"), // frontDistance); - } - if (_rangeFinderBack && _rangeFinderBack->distance < 5) { - _airSpeedCommand = 0; - _groundSpeedCommand = 0; + } + if (_rangeFinderBack && _rangeFinderBack->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; - } + } - if (_rangeFinderLeft && _rangeFinderLeft->distance < 5) { - _airSpeedCommand = 0; - _groundSpeedCommand = 0; - } + if (_rangeFinderLeft && _rangeFinderLeft->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; + } - if (_rangeFinderRight && _rangeFinderRight->distance < 5) { - _airSpeedCommand = 0; - _groundSpeedCommand = 0; - } + if (_rangeFinderRight && _rangeFinderRight->distance < 5) { + _airSpeedCommand = 0; + _groundSpeedCommand = 0; + } } void MavlinkGuide::nextCommand() { - // within 1 seconds, check if more than 5 calls to next command occur - // if they do, go to home waypoint - if (millis() - _nextCommandTimer < 1000) { - if (_nextCommandCalls > 5) { - Serial.println("commands loading too fast, returning home"); - setCurrentIndex(0); - setNumberOfCommands(1); - _nextCommandCalls = 0; - _nextCommandTimer = millis(); - return; - } - _nextCommandCalls++; - } else { - _nextCommandTimer = millis(); - _nextCommandCalls = 0; - } + // within 1 seconds, check if more than 5 calls to next command occur + // if they do, go to home waypoint + if (millis() - _nextCommandTimer < 1000) { + if (_nextCommandCalls > 5) { + Serial.println("commands loading too fast, returning home"); + setCurrentIndex(0); + setNumberOfCommands(1); + _nextCommandCalls = 0; + _nextCommandTimer = millis(); + return; + } + _nextCommandCalls++; + } else { + _nextCommandTimer = millis(); + _nextCommandCalls = 0; + } - _cmdIndex = getNextIndex(); - //Serial.print("cmd : "); Serial.println(int(_cmdIndex)); - //Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex())); - //Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands())); - _command = AP_MavlinkCommand(getCurrentIndex()); - _previousCommand = AP_MavlinkCommand(getPreviousIndex()); + _cmdIndex = getNextIndex(); + //Serial.print("cmd : "); Serial.println(int(_cmdIndex)); + //Serial.print("cmd prev : "); Serial.println(int(getPreviousIndex())); + //Serial.print("cmd num : "); Serial.println(int(getNumberOfCommands())); + _command = AP_MavlinkCommand(getCurrentIndex()); + _previousCommand = AP_MavlinkCommand(getPreviousIndex()); } void MavlinkGuide::handleCommand() { - // TODO handle more commands - switch (_command.getCommand()) { + // TODO handle more commands + switch (_command.getCommand()) { - case MAV_CMD_NAV_WAYPOINT: { + case MAV_CMD_NAV_WAYPOINT: { - // if we don't have enough waypoint for cross track calcs - // go home - if (_numberOfCommands == 1) { - _mode = MAV_NAV_RETURNING; - _altitudeCommand = AP_MavlinkCommand::home.getAlt(); - _headingCommand = AP_MavlinkCommand::home.bearingTo( - _navigator->getLat_degInt(), _navigator->getLon_degInt()) - + 180 * deg2Rad; - if (_headingCommand > 360 * deg2Rad) - _headingCommand -= 360 * deg2Rad; + // if we don't have enough waypoint for cross track calcs + // go home + if (_numberOfCommands == 1) { + _mode = MAV_NAV_RETURNING; + _altitudeCommand = AP_MavlinkCommand::home.getAlt(); + _headingCommand = AP_MavlinkCommand::home.bearingTo( + _navigator->getLat_degInt(), _navigator->getLon_degInt()) + + 180 * deg2Rad; + if (_headingCommand > 360 * deg2Rad) + _headingCommand -= 360 * deg2Rad; - //_hal->debug->printf_P(PSTR("going home: bearing: %f distance: %f\n"), - //headingCommand,AP_MavlinkCommand::home.distanceTo(_navigator->getLat_degInt(),_navigator->getLon_degInt())); - - // if we have 2 or more waypoints do x track navigation - } else { - _mode = MAV_NAV_WAYPOINT; - float alongTrack = _command.alongTrack(_previousCommand, - _navigator->getLat_degInt(), - _navigator->getLon_degInt()); - float distanceToNext = _command.distanceTo( - _navigator->getLat_degInt(), _navigator->getLon_degInt()); - float segmentLength = _previousCommand.distanceTo(_command); - if (distanceToNext < _command.getRadius() || alongTrack - > segmentLength) - { - Serial.println("waypoint reached"); - nextCommand(); - } - _altitudeCommand = _command.getAlt(); - float dXt = _command.crossTrack(_previousCommand, - _navigator->getLat_degInt(), - _navigator->getLon_degInt()); - float temp = dXt * _crossTrackGain * deg2Rad; // crosstrack gain, rad/m - if (temp > _crossTrackLim * deg2Rad) - temp = _crossTrackLim * deg2Rad; - if (temp < -_crossTrackLim * deg2Rad) - temp = -_crossTrackLim * deg2Rad; - float bearing = _previousCommand.bearingTo(_command); - _headingCommand = bearing - temp; - //_hal->debug->printf_P( - //PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\n"), - //bearing * rad2Deg, dXt, _headingCommand * rad2Deg, distanceToNext, alongTrack); - } + //_hal->debug->printf_P(PSTR("going home: bearing: %f distance: %f\n"), + //headingCommand,AP_MavlinkCommand::home.distanceTo(_navigator->getLat_degInt(),_navigator->getLon_degInt())); - _groundSpeedCommand = _velocityCommand; + // if we have 2 or more waypoints do x track navigation + } else { + _mode = MAV_NAV_WAYPOINT; + float alongTrack = _command.alongTrack(_previousCommand, + _navigator->getLat_degInt(), + _navigator->getLon_degInt()); + float distanceToNext = _command.distanceTo( + _navigator->getLat_degInt(), _navigator->getLon_degInt()); + float segmentLength = _previousCommand.distanceTo(_command); + if (distanceToNext < _command.getRadius() || alongTrack + > segmentLength) + { + Serial.println("waypoint reached"); + nextCommand(); + } + _altitudeCommand = _command.getAlt(); + float dXt = _command.crossTrack(_previousCommand, + _navigator->getLat_degInt(), + _navigator->getLon_degInt()); + float temp = dXt * _crossTrackGain * deg2Rad; // crosstrack gain, rad/m + if (temp > _crossTrackLim * deg2Rad) + temp = _crossTrackLim * deg2Rad; + if (temp < -_crossTrackLim * deg2Rad) + temp = -_crossTrackLim * deg2Rad; + float bearing = _previousCommand.bearingTo(_command); + _headingCommand = bearing - temp; + //_hal->debug->printf_P( + //PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\n"), + //bearing * rad2Deg, dXt, _headingCommand * rad2Deg, distanceToNext, alongTrack); + } - // calculate pN,pE,pD from home and gps coordinates - _pNCmd = _command.getPN(_navigator->getLat_degInt(), - _navigator->getLon_degInt()); - _pECmd = _command.getPE(_navigator->getLat_degInt(), - _navigator->getLon_degInt()); - _pDCmd = _command.getPD(_navigator->getAlt_intM()); + _groundSpeedCommand = _velocityCommand; - // debug - //_hal->debug->printf_P( - //PSTR("guide loop, number: %d, current index: %d, previous index: %d\n"), - //getNumberOfCommands(), - //getCurrentIndex(), - //getPreviousIndex()); + // calculate pN,pE,pD from home and gps coordinates + _pNCmd = _command.getPN(_navigator->getLat_degInt(), + _navigator->getLon_degInt()); + _pECmd = _command.getPE(_navigator->getLat_degInt(), + _navigator->getLon_degInt()); + _pDCmd = _command.getPD(_navigator->getAlt_intM()); - break; - } + // debug + //_hal->debug->printf_P( + //PSTR("guide loop, number: %d, current index: %d, previous index: %d\n"), + //getNumberOfCommands(), + //getCurrentIndex(), + //getPreviousIndex()); + + break; + } // case MAV_CMD_CONDITION_CHANGE_ALT: // case MAV_CMD_CONDITION_DELAY: // case MAV_CMD_CONDITION_DISTANCE: @@ -224,12 +234,12 @@ void MavlinkGuide::handleCommand() { // case MAV_CMD_NAV_PATHPLANNING: // case MAV_CMD_NAV_RETURN_TO_LAUNCH: // case MAV_CMD_NAV_TAKEOFF: - default: - // unhandled command, skip - Serial.println("unhandled command"); - nextCommand(); - break; - } + default: + // unhandled command, skip + Serial.println("unhandled command"); + nextCommand(); + break; + } } } // namespace apo diff --git a/libraries/APO/AP_Guide.h b/libraries/APO/AP_Guide.h index 0944620247..72a8d1b115 100644 --- a/libraries/APO/AP_Guide.h +++ b/libraries/APO/AP_Guide.h @@ -33,116 +33,117 @@ class AP_HardwareAbstractionLayer; class AP_Guide { public: - /** - * This is the constructor, which requires a link to the navigator. - * @param navigator This is the navigator pointer. - */ - AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal); + /** + * This is the constructor, which requires a link to the navigator. + * @param navigator This is the navigator pointer. + */ + AP_Guide(AP_Navigator * navigator, AP_HardwareAbstractionLayer * hal); - virtual void update() = 0; + virtual void update() = 0; - virtual void nextCommand() = 0; + virtual void nextCommand() = 0; - MAV_NAV getMode() const { - return _mode; - } - uint8_t getCurrentIndex() { - return _cmdIndex; - } + MAV_NAV getMode() const { + return _mode; + } + uint8_t getCurrentIndex() { + return _cmdIndex; + } - void setCurrentIndex(uint8_t val); + void setCurrentIndex(uint8_t val); - uint8_t getNumberOfCommands() { - return _numberOfCommands; - } + uint8_t getNumberOfCommands() { + return _numberOfCommands; + } - void setNumberOfCommands(uint8_t val) { - _numberOfCommands.set_and_save(val); - } + void setNumberOfCommands(uint8_t val) { + _numberOfCommands.set_and_save(val); + } - uint8_t getPreviousIndex() { - // find previous waypoint, TODO, handle non-nav commands - int16_t prevIndex = int16_t(getCurrentIndex()) - 1; - if (prevIndex < 0) - prevIndex = getNumberOfCommands() - 1; - return (uint8_t) prevIndex; - } + uint8_t getPreviousIndex() { + // find previous waypoint, TODO, handle non-nav commands + int16_t prevIndex = int16_t(getCurrentIndex()) - 1; + if (prevIndex < 0) + prevIndex = getNumberOfCommands() - 1; + return (uint8_t) prevIndex; + } - uint8_t getNextIndex() { - // find previous waypoint, TODO, handle non-nav commands - int16_t nextIndex = int16_t(getCurrentIndex()) + 1; - if (nextIndex > (getNumberOfCommands() - 1)) - nextIndex = 0; - return nextIndex; - } + uint8_t getNextIndex() { + // find previous waypoint, TODO, handle non-nav commands + int16_t nextIndex = int16_t(getCurrentIndex()) + 1; + if (nextIndex > (getNumberOfCommands() - 1)) + nextIndex = 0; + return nextIndex; + } - float getHeadingCommand() { - return _headingCommand; - } - float getAirSpeedCommand() { - return _airSpeedCommand; - } - float getGroundSpeedCommand() { - return _groundSpeedCommand; - } - float getAltitudeCommand() { - return _altitudeCommand; - } - float getPNCmd() { - return _pNCmd; - } - float getPECmd() { - return _pECmd; - } - float getPDCmd() { - return _pDCmd; - } - MAV_NAV getMode() { - return _mode; - } - uint8_t getCommandIndex() { - return _cmdIndex; - } + float getHeadingError(); + + float getHeadingCommand() { + return _headingCommand; + } + float getAirSpeedCommand() { + return _airSpeedCommand; + } + float getGroundSpeedCommand() { + return _groundSpeedCommand; + } + float getAltitudeCommand() { + return _altitudeCommand; + } + float getPNCmd() { + return _pNCmd; + } + float getPECmd() { + return _pECmd; + } + float getPDCmd() { + return _pDCmd; + } + MAV_NAV getMode() { + return _mode; + } + uint8_t getCommandIndex() { + return _cmdIndex; + } protected: - AP_Navigator * _navigator; - AP_HardwareAbstractionLayer * _hal; - AP_MavlinkCommand _command, _previousCommand; - float _headingCommand; - float _airSpeedCommand; - float _groundSpeedCommand; - float _altitudeCommand; - float _pNCmd; - float _pECmd; - float _pDCmd; - MAV_NAV _mode; - AP_Uint8 _numberOfCommands; - AP_Uint8 _cmdIndex; - uint16_t _nextCommandCalls; - uint16_t _nextCommandTimer; + AP_Navigator * _navigator; + AP_HardwareAbstractionLayer * _hal; + AP_MavlinkCommand _command, _previousCommand; + float _headingCommand; + float _airSpeedCommand; + float _groundSpeedCommand; + float _altitudeCommand; + float _pNCmd; + float _pECmd; + float _pDCmd; + MAV_NAV _mode; + AP_Uint8 _numberOfCommands; + AP_Uint8 _cmdIndex; + uint16_t _nextCommandCalls; + uint16_t _nextCommandTimer; }; class MavlinkGuide: public AP_Guide { public: - MavlinkGuide(AP_Navigator * navigator, - AP_HardwareAbstractionLayer * hal); - virtual void update(); - void nextCommand(); - void handleCommand(); + MavlinkGuide(AP_Navigator * navigator, + AP_HardwareAbstractionLayer * hal, float velCmd, float xt, float xtLim); + virtual void update(); + void nextCommand(); + void handleCommand(); private: - RangeFinder * _rangeFinderFront; - RangeFinder * _rangeFinderBack; - RangeFinder * _rangeFinderLeft; - RangeFinder * _rangeFinderRight; - AP_Var_group _group; - AP_Float _velocityCommand; - AP_Float _crossTrackGain; - AP_Float _crossTrackLim; + RangeFinder * _rangeFinderFront; + RangeFinder * _rangeFinderBack; + RangeFinder * _rangeFinderLeft; + RangeFinder * _rangeFinderRight; + AP_Var_group _group; + AP_Float _velocityCommand; + AP_Float _crossTrackGain; + AP_Float _crossTrackLim; }; } // namespace apo #endif // AP_Guide_H - // vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_HardwareAbstractionLayer.cpp b/libraries/APO/AP_HardwareAbstractionLayer.cpp index afa06769ab..9939e90e57 100644 --- a/libraries/APO/AP_HardwareAbstractionLayer.cpp +++ b/libraries/APO/AP_HardwareAbstractionLayer.cpp @@ -6,3 +6,4 @@ */ #include "AP_HardwareAbstractionLayer.h" +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_HardwareAbstractionLayer.h b/libraries/APO/AP_HardwareAbstractionLayer.h index 422bb55d36..9b3b9e2810 100644 --- a/libraries/APO/AP_HardwareAbstractionLayer.h +++ b/libraries/APO/AP_HardwareAbstractionLayer.h @@ -28,134 +28,149 @@ class AP_BatteryMonitor; // enumerations enum halMode_t { - MODE_LIVE, MODE_HIL_CNTL, -/*MODE_HIL_NAV*/}; + MODE_LIVE, MODE_HIL_CNTL, + /*MODE_HIL_NAV*/ +}; enum board_t { - BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2 + BOARD_ARDUPILOTMEGA_1280, BOARD_ARDUPILOTMEGA_2560, BOARD_ARDUPILOTMEGA_2 }; enum vehicle_t { - VEHICLE_CAR, VEHICLE_QUAD, VEHICLE_PLANE, VEHICLE_BOAT, VEHICLE_TANK + VEHICLE_CAR, VEHICLE_QUAD, VEHICLE_PLANE, VEHICLE_BOAT, VEHICLE_TANK }; class AP_HardwareAbstractionLayer { public: - // default ctors on pointers called on pointers here, this - // allows NULL to be used as a boolean for if the device was - // initialized - AP_HardwareAbstractionLayer(halMode_t mode, board_t board, - vehicle_t vehicle, uint8_t heartBeatTimeout) : - adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(), rc(), gcs(), - hil(), debug(), load(), lastHeartBeat(), - _heartBeatTimeout(heartBeatTimeout), _mode(mode), - _board(board), _vehicle(vehicle), _state(MAV_STATE_UNINIT) { + // default ctors on pointers called on pointers here, this + // allows NULL to be used as a boolean for if the device was + // initialized + AP_HardwareAbstractionLayer(halMode_t mode, board_t board, + vehicle_t vehicle, uint8_t heartBeatTimeout) : + adc(), gps(), baro(), compass(), rangeFinders(), imu(), batteryMonitor(), rc(), gcs(), + hil(), debug(), load(), lastHeartBeat(), + _heartBeatTimeout(heartBeatTimeout), _mode(mode), + _board(board), _vehicle(vehicle), _state(MAV_STATE_UNINIT) { - /* - * Board specific hardware initialization - */ - if (board == BOARD_ARDUPILOTMEGA_1280) { - slideSwitchPin = 40; - pushButtonPin = 41; - aLedPin = 37; - bLedPin = 36; - cLedPin = 35; - eepromMaxAddr = 1024; - pinMode(aLedPin, OUTPUT); // extra led - pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; - pinMode(cLedPin, OUTPUT); // gps led - pinMode(slideSwitchPin, INPUT); - pinMode(pushButtonPin, INPUT); - DDRL |= B00000100; // set port L, pint 2 to output for the relay - } else if (board == BOARD_ARDUPILOTMEGA_2560) { - slideSwitchPin = 40; - pushButtonPin = 41; - aLedPin = 37; - bLedPin = 36; - cLedPin = 35; - eepromMaxAddr = 2048; - pinMode(aLedPin, OUTPUT); // extra led - pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; - pinMode(cLedPin, OUTPUT); // gps led - pinMode(slideSwitchPin, INPUT); - pinMode(pushButtonPin, INPUT); - DDRL |= B00000100; // set port L, pint 2 to output for the relay - } - } + /* + * Board specific hardware initialization + */ + if (board == BOARD_ARDUPILOTMEGA_1280) { + slideSwitchPin = 40; + pushButtonPin = 41; + aLedPin = 37; + bLedPin = 36; + cLedPin = 35; + eepromMaxAddr = 1024; + pinMode(aLedPin, OUTPUT); // extra led + pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; + pinMode(cLedPin, OUTPUT); // gps led + pinMode(slideSwitchPin, INPUT); + pinMode(pushButtonPin, INPUT); + DDRL |= B00000100; // set port L, pint 2 to output for the relay + } else if (board == BOARD_ARDUPILOTMEGA_2560) { + slideSwitchPin = 40; + pushButtonPin = 41; + aLedPin = 37; + bLedPin = 36; + cLedPin = 35; + eepromMaxAddr = 2048; + pinMode(aLedPin, OUTPUT); // extra led + pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; + pinMode(cLedPin, OUTPUT); // gps led + pinMode(slideSwitchPin, INPUT); + pinMode(pushButtonPin, INPUT); + DDRL |= B00000100; // set port L, pint 2 to output for the relay + } else if (board == BOARD_ARDUPILOTMEGA_2) { + slideSwitchPin = 40; + pushButtonPin = 41; + aLedPin = 37; + bLedPin = 36; + cLedPin = 35; + eepromMaxAddr = 2048; + pinMode(aLedPin, OUTPUT); // extra led + pinMode(bLedPin, OUTPUT); // imu ledclass AP_CommLink; + pinMode(cLedPin, OUTPUT); // gps led + pinMode(slideSwitchPin, INPUT); + pinMode(pushButtonPin, INPUT); + DDRL |= B00000100; // set port L, pint 2 to output for the relay + } + } - /** - * Sensors - */ - AP_ADC * adc; - GPS * gps; - APM_BMP085_Class * baro; - Compass * compass; - Vector rangeFinders; - IMU * imu; - AP_BatteryMonitor * batteryMonitor; + /** + * Sensors + */ + AP_ADC * adc; + GPS * gps; + APM_BMP085_Class * baro; + Compass * compass; + Vector rangeFinders; + IMU * imu; + AP_BatteryMonitor * batteryMonitor; - /** - * Radio Channels - */ - Vector rc; + /** + * Radio Channels + */ + Vector rc; - /** - * Communication Channels - */ - AP_CommLink * gcs; - AP_CommLink * hil; - FastSerial * debug; + /** + * Communication Channels + */ + AP_CommLink * gcs; + AP_CommLink * hil; + FastSerial * debug; - /** - * data - */ - uint8_t load; - uint32_t lastHeartBeat; + /** + * data + */ + uint8_t load; + uint32_t lastHeartBeat; - /** - * settings - */ - uint8_t slideSwitchPin; - uint8_t pushButtonPin; - uint8_t aLedPin; - uint8_t bLedPin; - uint8_t cLedPin; - uint16_t eepromMaxAddr; + /** + * settings + */ + uint8_t slideSwitchPin; + uint8_t pushButtonPin; + uint8_t aLedPin; + uint8_t bLedPin; + uint8_t cLedPin; + uint16_t eepromMaxAddr; - // accessors - halMode_t getMode() { - return _mode; - } - board_t getBoard() { - return _board; - } - vehicle_t getVehicle() { - return _vehicle; - } - MAV_STATE getState() { - return _state; - } - void setState(MAV_STATE state) { - _state = state; - } + // accessors + halMode_t getMode() { + return _mode; + } + board_t getBoard() { + return _board; + } + vehicle_t getVehicle() { + return _vehicle; + } + MAV_STATE getState() { + return _state; + } + void setState(MAV_STATE state) { + _state = state; + } - bool heartBeatLost() { - if (_heartBeatTimeout == 0) - return false; - else - return ((micros() - lastHeartBeat) / 1e6) > _heartBeatTimeout; - } + bool heartBeatLost() { + if (_heartBeatTimeout == 0) + return false; + else + return ((micros() - lastHeartBeat) / 1e6) > _heartBeatTimeout; + } private: - // enumerations - uint8_t _heartBeatTimeout; - halMode_t _mode; - board_t _board; - vehicle_t _vehicle; - MAV_STATE _state; + // enumerations + uint8_t _heartBeatTimeout; + halMode_t _mode; + board_t _board; + vehicle_t _vehicle; + MAV_STATE _state; }; -} +} // namespace apo #endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_MavlinkCommand.cpp b/libraries/APO/AP_MavlinkCommand.cpp index 987e2c0dbe..9fd6cd5627 100644 --- a/libraries/APO/AP_MavlinkCommand.cpp +++ b/libraries/APO/AP_MavlinkCommand.cpp @@ -5,183 +5,205 @@ * Author: jgoppert */ +#include "../FastSerial/FastSerial.h" #include "AP_MavlinkCommand.h" namespace apo { AP_MavlinkCommand::AP_MavlinkCommand(const AP_MavlinkCommand & v) : - _data(v._data), _seq(v._seq) { - //if (FastSerial::getInitialized(0)) Serial.println("copy ctor"); + _data(v._data), _seq(v._seq) { + //if (FastSerial::getInitialized(0)) Serial.println("copy ctor"); } AP_MavlinkCommand::AP_MavlinkCommand(uint16_t index, bool doLoad) : - _data(k_commands + index), _seq(index) { + _data(k_commands + index), _seq(index) { - if (FastSerial::getInitialized(0)) { - Serial.println("index ctor"); - Serial.println("++"); - Serial.print("index: "); Serial.println(index); - Serial.print("key: "); Serial.println(k_commands + index); - Serial.println("++"); - } + if (FastSerial::getInitialized(0)) { + Serial.println("index ctor"); + Serial.println("++"); + Serial.print("index: "); + Serial.println(index); + Serial.print("key: "); + Serial.println(k_commands + index); + Serial.println("++"); + } - // default values for structure - _data.get().command = MAV_CMD_NAV_WAYPOINT; - _data.get().autocontinue = true; - _data.get().frame = MAV_FRAME_GLOBAL; - _data.get().param1 = 0; - _data.get().param2 = 10; // radius of 10 meters - _data.get().param3 = 0; - _data.get().param4 = 0; - _data.get().x = 0; - _data.get().y = 0; - _data.get().z = 1000; + // default values for structure + _data.get().command = MAV_CMD_NAV_WAYPOINT; + _data.get().autocontinue = true; + _data.get().frame = MAV_FRAME_GLOBAL; + _data.get().param1 = 0; + _data.get().param2 = 10; // radius of 10 meters + _data.get().param3 = 0; + _data.get().param4 = 0; + _data.get().x = 0; + _data.get().y = 0; + _data.get().z = 1000; - // This is a failsafe measure to stop trying to load a command if it can't load - if (doLoad && !load()) { - Serial.println("load failed, reverting to home waypoint"); - _data = AP_MavlinkCommand::home._data; - _seq = AP_MavlinkCommand::home._seq; - } + // This is a failsafe measure to stop trying to load a command if it can't load + if (doLoad && !load()) { + Serial.println("load failed, reverting to home waypoint"); + _data = AP_MavlinkCommand::home._data; + _seq = AP_MavlinkCommand::home._seq; + } } AP_MavlinkCommand::AP_MavlinkCommand(const mavlink_waypoint_t & cmd) : - _data(k_commands + cmd.seq), _seq(cmd.seq) { - setCommand(MAV_CMD(cmd.command)); - setAutocontinue(cmd.autocontinue); - setFrame(MAV_FRAME(cmd.frame)); - setParam1(cmd.param1); - setParam2(cmd.param2); - setParam3(cmd.param3); - setParam4(cmd.param4); - setX(cmd.x); - setY(cmd.y); - setZ(cmd.z); - save(); + _data(k_commands + cmd.seq), _seq(cmd.seq) { + setCommand(MAV_CMD(cmd.command)); + setAutocontinue(cmd.autocontinue); + setFrame(MAV_FRAME(cmd.frame)); + setParam1(cmd.param1); + setParam2(cmd.param2); + setParam3(cmd.param3); + setParam4(cmd.param4); + setX(cmd.x); + setY(cmd.y); + setZ(cmd.z); + save(); - // reload home if sent - if (cmd.seq == 0) home.load(); + // reload home if sent + if (cmd.seq == 0) home.load(); - Serial.println("============================================================"); - Serial.println("storing new command from mavlink_waypoint_t"); - Serial.print("key: "); Serial.println(_data.key(),DEC); - Serial.print("number: "); Serial.println(cmd.seq,DEC); - Serial.print("command: "); Serial.println(getCommand()); - Serial.print("autocontinue: "); Serial.println(getAutocontinue(),DEC); - Serial.print("frame: "); Serial.println(getFrame(),DEC); - Serial.print("1000*param1: "); Serial.println(int(1000*getParam1()),DEC); - Serial.print("1000*param2: "); Serial.println(int(1000*getParam2()),DEC); - Serial.print("1000*param3: "); Serial.println(int(1000*getParam3()),DEC); - Serial.print("1000*param4: "); Serial.println(int(1000*getParam4()),DEC); - Serial.print("1000*x0: "); Serial.println(int(1000*cmd.x),DEC); - Serial.print("1000*y0: "); Serial.println(int(1000*cmd.y),DEC); - Serial.print("1000*z0: "); Serial.println(int(1000*cmd.z),DEC); - Serial.print("1000*x: "); Serial.println(int(1000*getX()),DEC); - Serial.print("1000*y: "); Serial.println(int(1000*getY()),DEC); - Serial.print("1000*z: "); Serial.println(int(1000*getZ()),DEC); + Serial.println("============================================================"); + Serial.println("storing new command from mavlink_waypoint_t"); + Serial.print("key: "); + Serial.println(_data.key(),DEC); + Serial.print("number: "); + Serial.println(cmd.seq,DEC); + Serial.print("command: "); + Serial.println(getCommand()); + Serial.print("autocontinue: "); + Serial.println(getAutocontinue(),DEC); + Serial.print("frame: "); + Serial.println(getFrame(),DEC); + Serial.print("1000*param1: "); + Serial.println(int(1000*getParam1()),DEC); + Serial.print("1000*param2: "); + Serial.println(int(1000*getParam2()),DEC); + Serial.print("1000*param3: "); + Serial.println(int(1000*getParam3()),DEC); + Serial.print("1000*param4: "); + Serial.println(int(1000*getParam4()),DEC); + Serial.print("1000*x0: "); + Serial.println(int(1000*cmd.x),DEC); + Serial.print("1000*y0: "); + Serial.println(int(1000*cmd.y),DEC); + Serial.print("1000*z0: "); + Serial.println(int(1000*cmd.z),DEC); + Serial.print("1000*x: "); + Serial.println(int(1000*getX()),DEC); + Serial.print("1000*y: "); + Serial.println(int(1000*getY()),DEC); + Serial.print("1000*z: "); + Serial.println(int(1000*getZ()),DEC); - load(); + load(); - Serial.print("1000*x1: "); Serial.println(int(1000*getX()),DEC); - Serial.print("1000*y1: "); Serial.println(int(1000*getY()),DEC); - Serial.print("1000*z1: "); Serial.println(int(1000*getZ()),DEC); - Serial.println("============================================================"); - Serial.flush(); + Serial.print("1000*x1: "); + Serial.println(int(1000*getX()),DEC); + Serial.print("1000*y1: "); + Serial.println(int(1000*getY()),DEC); + Serial.print("1000*z1: "); + Serial.println(int(1000*getZ()),DEC); + Serial.println("============================================================"); + Serial.flush(); } mavlink_waypoint_t AP_MavlinkCommand::convert(uint8_t current) const { - mavlink_waypoint_t mavCmd; - mavCmd.seq = getSeq(); - mavCmd.command = getCommand(); - mavCmd.frame = getFrame(); - mavCmd.param1 = getParam1(); - mavCmd.param2 = getParam2(); - mavCmd.param3 = getParam3(); - mavCmd.param4 = getParam4(); - mavCmd.x = getX(); - mavCmd.y = getY(); - mavCmd.z = getZ(); - mavCmd.autocontinue = getAutocontinue(); - mavCmd.current = (getSeq() == current); - mavCmd.target_component = mavlink_system.compid; - mavCmd.target_system = mavlink_system.sysid; - return mavCmd; + mavlink_waypoint_t mavCmd; + mavCmd.seq = getSeq(); + mavCmd.command = getCommand(); + mavCmd.frame = getFrame(); + mavCmd.param1 = getParam1(); + mavCmd.param2 = getParam2(); + mavCmd.param3 = getParam3(); + mavCmd.param4 = getParam4(); + mavCmd.x = getX(); + mavCmd.y = getY(); + mavCmd.z = getZ(); + mavCmd.autocontinue = getAutocontinue(); + mavCmd.current = (getSeq() == current); + mavCmd.target_component = mavlink_system.compid; + mavCmd.target_system = mavlink_system.sysid; + return mavCmd; } float AP_MavlinkCommand::bearingTo(const AP_MavlinkCommand & next) const { - float deltaLon = next.getLon() - getLon(); - /* - Serial.print("Lon: "); Serial.println(getLon()); - Serial.print("nextLon: "); Serial.println(next.getLon()); - Serial.print("deltaLonDeg * 1e7: "); Serial.println(deltaLon*rad2DegInt); - */ - float bearing = atan2( - sin(deltaLon) * cos(next.getLat()), - cos(getLat()) * sin(next.getLat()) - sin(getLat()) * cos( - next.getLat()) * cos(deltaLon)); - return bearing; + float deltaLon = next.getLon() - getLon(); + /* + Serial.print("Lon: "); Serial.println(getLon()); + Serial.print("nextLon: "); Serial.println(next.getLon()); + Serial.print("deltaLonDeg * 1e7: "); Serial.println(deltaLon*rad2DegInt); + */ + float bearing = atan2( + sin(deltaLon) * cos(next.getLat()), + cos(getLat()) * sin(next.getLat()) - sin(getLat()) * cos( + next.getLat()) * cos(deltaLon)); + return bearing; } float AP_MavlinkCommand::bearingTo(int32_t latDegInt, int32_t lonDegInt) const { - // have to be careful to maintain the precision of the gps coordinate - float deltaLon = (lonDegInt - getLon_degInt()) * degInt2Rad; - float nextLat = latDegInt * degInt2Rad; - float bearing = atan2( - sin(deltaLon) * cos(nextLat), - cos(getLat()) * sin(nextLat) - sin(getLat()) * cos(nextLat) - * cos(deltaLon)); - if (bearing < 0) - bearing += 2 * M_PI; - return bearing; + // have to be careful to maintain the precision of the gps coordinate + float deltaLon = (lonDegInt - getLon_degInt()) * degInt2Rad; + float nextLat = latDegInt * degInt2Rad; + float bearing = atan2( + sin(deltaLon) * cos(nextLat), + cos(getLat()) * sin(nextLat) - sin(getLat()) * cos(nextLat) + * cos(deltaLon)); + if (bearing < 0) + bearing += 2 * M_PI; + return bearing; } float AP_MavlinkCommand::distanceTo(const AP_MavlinkCommand & next) const { - float sinDeltaLat2 = sin((getLat() - next.getLat()) / 2); - float sinDeltaLon2 = sin((getLon() - next.getLon()) / 2); - float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( - next.getLat()) * sinDeltaLon2 * sinDeltaLon2; - float c = 2 * atan2(sqrt(a), sqrt(1 - a)); - return rEarth * c; + float sinDeltaLat2 = sin((getLat() - next.getLat()) / 2); + float sinDeltaLon2 = sin((getLon() - next.getLon()) / 2); + float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( + next.getLat()) * sinDeltaLon2 * sinDeltaLon2; + float c = 2 * atan2(sqrt(a), sqrt(1 - a)); + return rEarth * c; } float AP_MavlinkCommand::distanceTo(int32_t lat_degInt, int32_t lon_degInt) const { - float sinDeltaLat2 = sin( - (lat_degInt - getLat_degInt()) * degInt2Rad / 2); - float sinDeltaLon2 = sin( - (lon_degInt - getLon_degInt()) * degInt2Rad / 2); - float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( - lat_degInt * degInt2Rad) * sinDeltaLon2 * sinDeltaLon2; - float c = 2 * atan2(sqrt(a), sqrt(1 - a)); - /* - Serial.print("wp lat_degInt: "); Serial.println(getLat_degInt()); - Serial.print("wp lon_degInt: "); Serial.println(getLon_degInt()); - Serial.print("lat_degInt: "); Serial.println(lat_degInt); - Serial.print("lon_degInt: "); Serial.println(lon_degInt); - Serial.print("sinDeltaLat2: "); Serial.println(sinDeltaLat2); - Serial.print("sinDeltaLon2: "); Serial.println(sinDeltaLon2); - */ - return rEarth * c; + float sinDeltaLat2 = sin( + (lat_degInt - getLat_degInt()) * degInt2Rad / 2); + float sinDeltaLon2 = sin( + (lon_degInt - getLon_degInt()) * degInt2Rad / 2); + float a = sinDeltaLat2 * sinDeltaLat2 + cos(getLat()) * cos( + lat_degInt * degInt2Rad) * sinDeltaLon2 * sinDeltaLon2; + float c = 2 * atan2(sqrt(a), sqrt(1 - a)); + /* + Serial.print("wp lat_degInt: "); Serial.println(getLat_degInt()); + Serial.print("wp lon_degInt: "); Serial.println(getLon_degInt()); + Serial.print("lat_degInt: "); Serial.println(lat_degInt); + Serial.print("lon_degInt: "); Serial.println(lon_degInt); + Serial.print("sinDeltaLat2: "); Serial.println(sinDeltaLat2); + Serial.print("sinDeltaLon2: "); Serial.println(sinDeltaLon2); + */ + return rEarth * c; } //calculates cross track of a current location float AP_MavlinkCommand::crossTrack(const AP_MavlinkCommand & previous, - int32_t lat_degInt, int32_t lon_degInt) const { - float d = previous.distanceTo(lat_degInt, lon_degInt); - float bCurrent = previous.bearingTo(lat_degInt, lon_degInt); - float bNext = previous.bearingTo(*this); - return asin(sin(d / rEarth) * sin(bCurrent - bNext)) * rEarth; + int32_t lat_degInt, int32_t lon_degInt) const { + float d = previous.distanceTo(lat_degInt, lon_degInt); + float bCurrent = previous.bearingTo(lat_degInt, lon_degInt); + float bNext = previous.bearingTo(*this); + return asin(sin(d / rEarth) * sin(bCurrent - bNext)) * rEarth; } // calculates along track distance of a current location float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous, - int32_t lat_degInt, int32_t lon_degInt) const { - // ignores lat/lon since single prec. - float dXt = this->crossTrack(previous,lat_degInt, lon_degInt); - float d = previous.distanceTo(lat_degInt, lon_degInt); - return dXt / tan(asin(dXt / d)); + int32_t lat_degInt, int32_t lon_degInt) const { + // ignores lat/lon since single prec. + float dXt = this->crossTrack(previous,lat_degInt, lon_degInt); + float d = previous.distanceTo(lat_degInt, lon_degInt); + return dXt / tan(asin(dXt / d)); } AP_MavlinkCommand AP_MavlinkCommand::home = AP_MavlinkCommand(0,false); -} +} // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_MavlinkCommand.h b/libraries/APO/AP_MavlinkCommand.h index a50002cb95..cf4beb47dd 100644 --- a/libraries/APO/AP_MavlinkCommand.h +++ b/libraries/APO/AP_MavlinkCommand.h @@ -12,364 +12,364 @@ #include "../AP_Common/AP_Common.h" #include "AP_Var_keys.h" #include "constants.h" -#include "../FastSerial/FastSerial.h" namespace apo { class AP_MavlinkCommand { private: - struct CommandStorage { - MAV_CMD command; - bool autocontinue; - MAV_FRAME frame; - float param1; - float param2; - float param3; - float param4; - float x; - float y; - float z; - }; - AP_VarS _data; - uint16_t _seq; + struct CommandStorage { + MAV_CMD command; + bool autocontinue; + MAV_FRAME frame; + float param1; + float param2; + float param3; + float param4; + float x; + float y; + float z; + }; + AP_VarS _data; + uint16_t _seq; public: - static AP_MavlinkCommand home; + static AP_MavlinkCommand home; - /** - * Copy Constructor - */ - AP_MavlinkCommand(const AP_MavlinkCommand & v); + /** + * Copy Constructor + */ + AP_MavlinkCommand(const AP_MavlinkCommand & v); - /** - * Basic Constructor - * @param index Start at zero. - */ - AP_MavlinkCommand(uint16_t index, bool doLoad = true); + /** + * Basic Constructor + * @param index Start at zero. + */ + AP_MavlinkCommand(uint16_t index, bool doLoad = true); - /** - * Constructor for copying/ saving from a mavlink waypoint. - * @param cmd The mavlink_waopint_t structure for the command. - */ - AP_MavlinkCommand(const mavlink_waypoint_t & cmd); + /** + * Constructor for copying/ saving from a mavlink waypoint. + * @param cmd The mavlink_waopint_t structure for the command. + */ + AP_MavlinkCommand(const mavlink_waypoint_t & cmd); - bool save() { - return _data.save(); - } - bool load() { - return _data.load(); - } - uint8_t getSeq() const { - return _seq; - } - bool getAutocontinue() const { - return _data.get().autocontinue; - } - void setAutocontinue( bool val) { - _data.get().autocontinue = val; - } - void setSeq(uint8_t val) { - _seq = val; - } - MAV_CMD getCommand() const { - return _data.get().command; - } - void setCommand(MAV_CMD val) { - _data.get().command = val; - } - MAV_FRAME getFrame() const { - return _data.get().frame; - } - void setFrame(MAV_FRAME val) { - _data.get().frame = val; - } - float getParam1() const { - return _data.get().param1; - } - void setParam1(float val) { - _data.get().param1 = val; - } - float getParam2() const { - return _data.get().param2; - } - void setParam2(float val) { - _data.get().param2 = val; - } - float getParam3() const { - return _data.get().param3; - } - void setParam3(float val) { - _data.get().param3 = val; - } - float getParam4() const { - return _data.get().param4; - } - void setParam4(float val) { - _data.get().param4 = val; - } - float getX() const { - return _data.get().x; - } - void setX(float val) { - _data.get().x = val; - } - float getY() const { - return _data.get().y; - } - void setY(float val) { - _data.get().y = val; - } - float getZ() const { - return _data.get().z; - } - void setZ(float val) { - _data.get().z = val; - } - float getLatDeg() const { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - return getX(); - break; - case MAV_FRAME_LOCAL: - case MAV_FRAME_LOCAL_ENU: - case MAV_FRAME_MISSION: - default: - return 0; - break; - } - } - void setLatDeg(float val) { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - setX(val); - break; - case MAV_FRAME_LOCAL: - case MAV_FRAME_LOCAL_ENU: - case MAV_FRAME_MISSION: - default: - break; - } - } - float getLonDeg() const { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - return getY(); - break; - case MAV_FRAME_LOCAL: - case MAV_FRAME_LOCAL_ENU: - case MAV_FRAME_MISSION: - default: - return 0; - break; - } - } - void setLonDeg(float val) { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - setY(val); - break; - case MAV_FRAME_LOCAL: - case MAV_FRAME_LOCAL_ENU: - case MAV_FRAME_MISSION: - default: - break; - } - } - void setLon(float val) { - setLonDeg(val * rad2Deg); - } - void setLon_degInt(int32_t val) { - setLonDeg(val / 1.0e7); - } - void setLat_degInt(int32_t val) { - setLatDeg(val / 1.0e7); - } - int32_t getLon_degInt() const { - return getLonDeg() * 1e7; - } - int32_t getLat_degInt() const { - return getLatDeg() * 1e7; - } - float getLon() const { - return getLonDeg() * deg2Rad; - } - float getLat() const { - return getLatDeg() * deg2Rad; - } - void setLat(float val) { - setLatDeg(val * rad2Deg); - } - float getAlt() const { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - return getZ(); - break; - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - case MAV_FRAME_LOCAL: - return -getZ() + home.getAlt(); - break; - case MAV_FRAME_LOCAL_ENU: - return getZ() + home.getAlt(); - break; - case MAV_FRAME_MISSION: - default: - return 0; - break; - } - } - /** - * set the altitude in meters - */ - void setAlt(float val) { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - setZ(val); - break; - case MAV_FRAME_LOCAL: - setZ(home.getLonDeg() - val); - break; - case MAV_FRAME_LOCAL_ENU: - setZ(val - home.getLonDeg()); - break; - case MAV_FRAME_MISSION: - default: - break; - } - } - /** - * Get the relative altitude to home - * @return relative altitude in meters - */ - float getRelAlt() const { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - return getZ() - home.getAlt(); - break; - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - case MAV_FRAME_LOCAL: - return -getZ(); - break; - case MAV_FRAME_LOCAL_ENU: - return getZ(); - break; - case MAV_FRAME_MISSION: - default: - return 0; - break; - } - } - /** - * set the relative altitude in meters from home (up) - */ - void setRelAlt(float val) { - switch (getFrame()) { - case MAV_FRAME_GLOBAL: - setZ(val + home.getAlt()); - break; - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - case MAV_FRAME_LOCAL: - setZ(-val); - break; - case MAV_FRAME_LOCAL_ENU: - setZ(val); - break; - case MAV_FRAME_MISSION: - break; - } - } + bool save() { + return _data.save(); + } + bool load() { + return _data.load(); + } + uint8_t getSeq() const { + return _seq; + } + bool getAutocontinue() const { + return _data.get().autocontinue; + } + void setAutocontinue( bool val) { + _data.get().autocontinue = val; + } + void setSeq(uint8_t val) { + _seq = val; + } + MAV_CMD getCommand() const { + return _data.get().command; + } + void setCommand(MAV_CMD val) { + _data.get().command = val; + } + MAV_FRAME getFrame() const { + return _data.get().frame; + } + void setFrame(MAV_FRAME val) { + _data.get().frame = val; + } + float getParam1() const { + return _data.get().param1; + } + void setParam1(float val) { + _data.get().param1 = val; + } + float getParam2() const { + return _data.get().param2; + } + void setParam2(float val) { + _data.get().param2 = val; + } + float getParam3() const { + return _data.get().param3; + } + void setParam3(float val) { + _data.get().param3 = val; + } + float getParam4() const { + return _data.get().param4; + } + void setParam4(float val) { + _data.get().param4 = val; + } + float getX() const { + return _data.get().x; + } + void setX(float val) { + _data.get().x = val; + } + float getY() const { + return _data.get().y; + } + void setY(float val) { + _data.get().y = val; + } + float getZ() const { + return _data.get().z; + } + void setZ(float val) { + _data.get().z = val; + } + float getLatDeg() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + return getX(); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + void setLatDeg(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setX(val); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + break; + } + } + float getLonDeg() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + return getY(); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + void setLonDeg(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setY(val); + break; + case MAV_FRAME_LOCAL: + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_MISSION: + default: + break; + } + } + void setLon(float val) { + setLonDeg(val * rad2Deg); + } + void setLon_degInt(int32_t val) { + setLonDeg(val / 1.0e7); + } + void setLat_degInt(int32_t val) { + setLatDeg(val / 1.0e7); + } + int32_t getLon_degInt() const { + return getLonDeg() * 1e7; + } + int32_t getLat_degInt() const { + return getLatDeg() * 1e7; + } + float getLon() const { + return getLonDeg() * deg2Rad; + } + float getLat() const { + return getLatDeg() * deg2Rad; + } + void setLat(float val) { + setLatDeg(val * rad2Deg); + } + float getAlt() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + return getZ(); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + return -getZ() + home.getAlt(); + break; + case MAV_FRAME_LOCAL_ENU: + return getZ() + home.getAlt(); + break; + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + /** + * set the altitude in meters + */ + void setAlt(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + setZ(val); + break; + case MAV_FRAME_LOCAL: + setZ(home.getLonDeg() - val); + break; + case MAV_FRAME_LOCAL_ENU: + setZ(val - home.getLonDeg()); + break; + case MAV_FRAME_MISSION: + default: + break; + } + } + /** + * Get the relative altitude to home + * @return relative altitude in meters + */ + float getRelAlt() const { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + return getZ() - home.getAlt(); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + return -getZ(); + break; + case MAV_FRAME_LOCAL_ENU: + return getZ(); + break; + case MAV_FRAME_MISSION: + default: + return 0; + break; + } + } + /** + * set the relative altitude in meters from home (up) + */ + void setRelAlt(float val) { + switch (getFrame()) { + case MAV_FRAME_GLOBAL: + setZ(val + home.getAlt()); + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_LOCAL: + setZ(-val); + break; + case MAV_FRAME_LOCAL_ENU: + setZ(val); + break; + case MAV_FRAME_MISSION: + break; + } + } - float getRadius() const { - return getParam2(); - } + float getRadius() const { + return getParam2(); + } - void setRadius(float val) { - setParam2(val); - } + void setRadius(float val) { + setParam2(val); + } - /** - * conversion for outbound packets to ground station - * @return output the mavlink_waypoint_t packet - */ - mavlink_waypoint_t convert(uint8_t current) const; + /** + * conversion for outbound packets to ground station + * @return output the mavlink_waypoint_t packet + */ + mavlink_waypoint_t convert(uint8_t current) const; - /** - * Calculate the bearing from this command to the next command - * @param next The command to calculate the bearing to. - * @return the bearing - */ - float bearingTo(const AP_MavlinkCommand & next) const; + /** + * Calculate the bearing from this command to the next command + * @param next The command to calculate the bearing to. + * @return the bearing + */ + float bearingTo(const AP_MavlinkCommand & next) const; - /** - * Bearing form this command to a gps coordinate in integer units - * @param latDegInt latitude in degrees E-7 - * @param lonDegInt longitude in degrees E-7 - * @return - */ - float bearingTo(int32_t latDegInt, int32_t lonDegInt) const; + /** + * Bearing form this command to a gps coordinate in integer units + * @param latDegInt latitude in degrees E-7 + * @param lonDegInt longitude in degrees E-7 + * @return + */ + float bearingTo(int32_t latDegInt, int32_t lonDegInt) const; - /** - * Distance to another command - * @param next The command to measure to. - * @return The distance in meters. - */ - float distanceTo(const AP_MavlinkCommand & next) const; + /** + * Distance to another command + * @param next The command to measure to. + * @return The distance in meters. + */ + float distanceTo(const AP_MavlinkCommand & next) const; - /** - * Distance to a gps coordinate in integer units - * @param latDegInt latitude in degrees E-7 - * @param lonDegInt longitude in degrees E-7 - * @return The distance in meters. - */ - float distanceTo(int32_t lat_degInt, int32_t lon_degInt) const; + /** + * Distance to a gps coordinate in integer units + * @param latDegInt latitude in degrees E-7 + * @param lonDegInt longitude in degrees E-7 + * @return The distance in meters. + */ + float distanceTo(int32_t lat_degInt, int32_t lon_degInt) const; - float getPN(int32_t lat_degInt, int32_t lon_degInt) const { - // local tangent approximation at this waypoint - float deltaLat = (lat_degInt - getLat_degInt()) * degInt2Rad; - return deltaLat * rEarth; - } + float getPN(int32_t lat_degInt, int32_t lon_degInt) const { + // local tangent approximation at this waypoint + float deltaLat = (lat_degInt - getLat_degInt()) * degInt2Rad; + return deltaLat * rEarth; + } - float getPE(int32_t lat_degInt, int32_t lon_degInt) const { - // local tangent approximation at this waypoint - float deltaLon = (lon_degInt - getLon_degInt()) * degInt2Rad; - return cos(getLat()) * deltaLon * rEarth; - } + float getPE(int32_t lat_degInt, int32_t lon_degInt) const { + // local tangent approximation at this waypoint + float deltaLon = (lon_degInt - getLon_degInt()) * degInt2Rad; + return cos(getLat()) * deltaLon * rEarth; + } - float getPD(int32_t alt_intM) const { - return -(alt_intM / scale_m - getAlt()); - } + float getPD(int32_t alt_intM) const { + return -(alt_intM / scale_m - getAlt()); + } - float getLat(float pN) const { + float getLat(float pN) const { - return pN / rEarth + getLat(); - } + return pN / rEarth + getLat(); + } - float getLon(float pE) const { + float getLon(float pE) const { - return pE / rEarth / cos(getLat()) + getLon(); - } + return pE / rEarth / cos(getLat()) + getLon(); + } - /** - * Gets altitude in meters - * @param pD alt in meters - * @return - */ - float getAlt(float pD) const { + /** + * Gets altitude in meters + * @param pD alt in meters + * @return + */ + float getAlt(float pD) const { - return getAlt() - pD; - } + return getAlt() - pD; + } - //calculates cross track of a current location - float crossTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; + //calculates cross track of a current location + float crossTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; - // calculates along track distance of a current location - float alongTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; + // calculates along track distance of a current location + float alongTrack(const AP_MavlinkCommand & previous, int32_t lat_degInt, int32_t lon_degInt) const; }; } // namespace apo #endif /* AP_MAVLINKCOMMAND_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Navigator.cpp b/libraries/APO/AP_Navigator.cpp index 61883cec41..70a2f3289c 100644 --- a/libraries/APO/AP_Navigator.cpp +++ b/libraries/APO/AP_Navigator.cpp @@ -15,180 +15,194 @@ #include "AP_Var_keys.h" #include "../AP_RangeFinder/AP_RangeFinder.h" #include "../AP_IMU/AP_IMU.h" +#include "../APM_BMP085/APM_BMP085_hil.h" #include "../APM_BMP085/APM_BMP085.h" namespace apo { AP_Navigator::AP_Navigator(AP_HardwareAbstractionLayer * hal) : - _hal(hal), _timeStamp(0), _roll(0), _rollRate(0), _pitch(0), - _pitchRate(0), _yaw(0), _yawRate(0), _airSpeed(0), - _groundSpeed(0), _vD(0), _lat_degInt(0), - _lon_degInt(0), _alt_intM(0) { + _hal(hal), _timeStamp(0), _roll(0), _rollRate(0), _pitch(0), + _pitchRate(0), _yaw(0), _yawRate(0), _airSpeed(0), + _groundSpeed(0), _vD(0), _lat_degInt(0), + _lon_degInt(0), _alt_intM(0) { } void AP_Navigator::calibrate() { } float AP_Navigator::getPD() const { - return AP_MavlinkCommand::home.getPD(getAlt_intM()); + return AP_MavlinkCommand::home.getPD(getAlt_intM()); } float AP_Navigator::getPE() const { - return AP_MavlinkCommand::home.getPE(getLat_degInt(), getLon_degInt()); + return AP_MavlinkCommand::home.getPE(getLat_degInt(), getLon_degInt()); } float AP_Navigator::getPN() const { - return AP_MavlinkCommand::home.getPN(getLat_degInt(), getLon_degInt()); + return AP_MavlinkCommand::home.getPN(getLat_degInt(), getLon_degInt()); } void AP_Navigator::setPD(float _pD) { - setAlt(AP_MavlinkCommand::home.getAlt(_pD)); + setAlt(AP_MavlinkCommand::home.getAlt(_pD)); } void AP_Navigator::setPE(float _pE) { - setLat(AP_MavlinkCommand::home.getLat(_pE)); + setLat(AP_MavlinkCommand::home.getLat(_pE)); } void AP_Navigator::setPN(float _pN) { - setLon(AP_MavlinkCommand::home.getLon(_pN)); + setLon(AP_MavlinkCommand::home.getLon(_pN)); } DcmNavigator::DcmNavigator(AP_HardwareAbstractionLayer * hal) : - AP_Navigator(hal), _dcm(), _imuOffsetAddress(0) { + AP_Navigator(hal), _dcm(), _imuOffsetAddress(0) { - // if orientation equal to front, store as front - /** - * rangeFinder is assigned values based on orientation which - * is specified in ArduPilotOne.pde. - */ - for (uint8_t i = 0; i < _hal-> rangeFinders.getSize(); i++) { - if (_hal->rangeFinders[i] == NULL) - continue; - if (_hal->rangeFinders[i]->orientation_x == 0 - && _hal->rangeFinders[i]->orientation_y == 0 - && _hal->rangeFinders[i]->orientation_z == 1) - _rangeFinderDown = _hal->rangeFinders[i]; - } + // if orientation equal to front, store as front + /** + * rangeFinder is assigned values based on orientation which + * is specified in ArduPilotOne.pde. + */ + for (uint8_t i = 0; i < _hal-> rangeFinders.getSize(); i++) { + if (_hal->rangeFinders[i] == NULL) + continue; + if (_hal->rangeFinders[i]->orientation_x == 0 + && _hal->rangeFinders[i]->orientation_y == 0 + && _hal->rangeFinders[i]->orientation_z == 1) + _rangeFinderDown = _hal->rangeFinders[i]; + } - if (_hal->getMode() == MODE_LIVE) { - if (_hal->adc) - _hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib); - if (_hal->imu) - _dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass); - if (_hal->compass) { - _dcm->set_compass(_hal->compass); + if (_hal->getMode() == MODE_LIVE) { - } - } + if (_hal->adc) { + _hal->imu = new AP_IMU_Oilpan(_hal->adc, k_sensorCalib); + } + + if (_hal->imu) { + _dcm = new AP_DCM(_hal->imu, _hal->gps, _hal->compass); + + // tune down dcm + _dcm->kp_roll_pitch(0.030000); + _dcm->ki_roll_pitch(0.00001278), // 50 hz I term + + // tune down compass in dcm + _dcm->kp_yaw(0.08); + _dcm->ki_yaw(0); + } + + if (_hal->compass) { + _dcm->set_compass(_hal->compass); + } + } } void DcmNavigator::calibrate() { - AP_Navigator::calibrate(); + AP_Navigator::calibrate(); - // TODO: handle cold/warm restart - if (_hal->imu) { - _hal->imu->init(IMU::COLD_START,delay); - } + // TODO: handle cold/warm restart + if (_hal->imu) { + _hal->imu->init(IMU::COLD_START,delay); + } } void DcmNavigator::updateFast(float dt) { - if (_hal->getMode() != MODE_LIVE) - return; + if (_hal->getMode() != MODE_LIVE) + return; - setTimeStamp(micros()); // if running in live mode, record new time stamp + setTimeStamp(micros()); // if running in live mode, record new time stamp - //_hal->debug->println_P(PSTR("nav loop")); + //_hal->debug->println_P(PSTR("nav loop")); - /** - * The altitued is read off the barometer by implementing the following formula: - * altitude (in m) = 44330*(1-(p/po)^(1/5.255)), - * where, po is pressure in Pa at sea level (101325 Pa). - * See http://www.sparkfun.com/tutorials/253 or type this formula - * in a search engine for more information. - * altInt contains the altitude in meters. - */ - if (_hal->baro) { + /** + * The altitued is read off the barometer by implementing the following formula: + * altitude (in m) = 44330*(1-(p/po)^(1/5.255)), + * where, po is pressure in Pa at sea level (101325 Pa). + * See http://www.sparkfun.com/tutorials/253 or type this formula + * in a search engine for more information. + * altInt contains the altitude in meters. + */ + if (_hal->baro) { - if (_rangeFinderDown != NULL && _rangeFinderDown->distance <= 695) - setAlt(_rangeFinderDown->distance); + if (_rangeFinderDown != NULL && _rangeFinderDown->distance <= 695) + setAlt(_rangeFinderDown->distance); - else { - float tmp = (_hal->baro->Press / 101325.0); - tmp = pow(tmp, 0.190295); - //setAlt(44330 * (1.0 - tmp)); //sets the altitude in meters XXX wrong, baro reads 0 press - setAlt(0.0); - } - } + else { + float tmp = (_hal->baro->Press / 101325.0); + tmp = pow(tmp, 0.190295); + //setAlt(44330 * (1.0 - tmp)); //sets the altitude in meters XXX wrong, baro reads 0 press + setAlt(0.0); + } + } - // dcm class for attitude - if (_dcm) { - _dcm->update_DCM_fast(); - setRoll(_dcm->roll); - setPitch(_dcm->pitch); - setYaw(_dcm->yaw); - setRollRate(_dcm->get_gyro().x); - setPitchRate(_dcm->get_gyro().y); - setYawRate(_dcm->get_gyro().z); + // dcm class for attitude + if (_dcm) { + _dcm->update_DCM_fast(); + setRoll(_dcm->roll); + setPitch(_dcm->pitch); + setYaw(_dcm->yaw); + setRollRate(_dcm->get_gyro().x); + setPitchRate(_dcm->get_gyro().y); + setYawRate(_dcm->get_gyro().z); - /* - * accel/gyro debug - */ - /* - Vector3f accel = _hal->imu->get_accel(); - Vector3f gyro = _hal->imu->get_gyro(); - Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), - accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); - */ - } + /* + * accel/gyro debug + */ + /* + Vector3f accel = _hal->imu->get_accel(); + Vector3f gyro = _hal->imu->get_gyro(); + Serial.printf_P(PSTR("accel: %f %f %f gyro: %f %f %f\n"), + accel.x,accel.y,accel.z,gyro.x,gyro.y,gyro.z); + */ + } } void DcmNavigator::updateSlow(float dt) { - if (_hal->getMode() != MODE_LIVE) - return; + if (_hal->getMode() != MODE_LIVE) + return; - setTimeStamp(micros()); // if running in live mode, record new time stamp + setTimeStamp(micros()); // if running in live mode, record new time stamp - if (_hal->gps) { - _hal->gps->update(); - updateGpsLight(); - if (_hal->gps->fix && _hal->gps->new_data) { - setLat_degInt(_hal->gps->latitude); - setLon_degInt(_hal->gps->longitude); - setAlt_intM(_hal->gps->altitude * 10); // gps in cm, intM in mm - setGroundSpeed(_hal->gps->ground_speed / 100.0); // gps is in cm/s - } - } + if (_hal->gps) { + _hal->gps->update(); + updateGpsLight(); + if (_hal->gps->fix && _hal->gps->new_data) { + setLat_degInt(_hal->gps->latitude); + setLon_degInt(_hal->gps->longitude); + setAlt_intM(_hal->gps->altitude * 10); // gps in cm, intM in mm + setGroundSpeed(_hal->gps->ground_speed / 100.0); // gps is in cm/s + } + } - if (_hal->compass) { - _hal->compass->read(); - _hal->compass->calculate(_dcm->get_dcm_matrix()); - _hal->compass->null_offsets(_dcm->get_dcm_matrix()); - //_hal->debug->printf_P(PSTR("heading: %f"), _hal->compass->heading); - } + if (_hal->compass) { + _hal->compass->read(); + _hal->compass->calculate(_dcm->get_dcm_matrix()); + _hal->compass->null_offsets(_dcm->get_dcm_matrix()); + //_hal->debug->printf_P(PSTR("heading: %f"), _hal->compass->heading); + } } void DcmNavigator::updateGpsLight(void) { - // GPS LED on if we have a fix or Blink GPS LED if we are receiving data - // --------------------------------------------------------------------- - static bool GPS_light = false; - switch (_hal->gps->status()) { - case (2): - //digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix. - break; + // GPS LED on if we have a fix or Blink GPS LED if we are receiving data + // --------------------------------------------------------------------- + static bool GPS_light = false; + switch (_hal->gps->status()) { + case (2): + //digitalWrite(C_LED_PIN, HIGH); //Turn LED C on when gps has valid fix. + break; - case (1): - if (_hal->gps->valid_read == true) { - GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock - if (GPS_light) { - digitalWrite(_hal->cLedPin, LOW); - } else { - digitalWrite(_hal->cLedPin, HIGH); - } - _hal->gps->valid_read = false; - } - break; + case (1): + if (_hal->gps->valid_read == true) { + GPS_light = !GPS_light; // Toggle light on and off to indicate gps messages being received, but no GPS fix lock + if (GPS_light) { + digitalWrite(_hal->cLedPin, LOW); + } else { + digitalWrite(_hal->cLedPin, HIGH); + } + _hal->gps->valid_read = false; + } + break; - default: - digitalWrite(_hal->cLedPin, LOW); - break; - } + default: + digitalWrite(_hal->cLedPin, LOW); + break; + } } } // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Navigator.h b/libraries/APO/AP_Navigator.h index 9be22e6caf..49db8c5982 100644 --- a/libraries/APO/AP_Navigator.h +++ b/libraries/APO/AP_Navigator.h @@ -33,195 +33,195 @@ class AP_HardwareAbstractionLayer; /// Navigator class class AP_Navigator { public: - AP_Navigator(AP_HardwareAbstractionLayer * hal); - virtual void calibrate(); - virtual void updateFast(float dt) = 0; - virtual void updateSlow(float dt) = 0; - float getPD() const; - float getPE() const; - float getPN() const; - void setPD(float _pD); - void setPE(float _pE); - void setPN(float _pN); + AP_Navigator(AP_HardwareAbstractionLayer * hal); + virtual void calibrate(); + virtual void updateFast(float dt) = 0; + virtual void updateSlow(float dt) = 0; + float getPD() const; + float getPE() const; + float getPN() const; + void setPD(float _pD); + void setPE(float _pE); + void setPN(float _pN); - float getAirSpeed() const { - return _airSpeed; - } + float getAirSpeed() const { + return _airSpeed; + } - int32_t getAlt_intM() const { - return _alt_intM; - } + int32_t getAlt_intM() const { + return _alt_intM; + } - float getAlt() const { - return _alt_intM / scale_m; - } + float getAlt() const { + return _alt_intM / scale_m; + } - void setAlt(float _alt) { - this->_alt_intM = _alt * scale_m; - } + void setAlt(float _alt) { + this->_alt_intM = _alt * scale_m; + } - float getLat() const { - //Serial.print("getLatfirst"); - //Serial.println(_lat_degInt * degInt2Rad); - return _lat_degInt * degInt2Rad; - } + float getLat() const { + //Serial.print("getLatfirst"); + //Serial.println(_lat_degInt * degInt2Rad); + return _lat_degInt * degInt2Rad; + } - void setLat(float _lat) { - //Serial.print("setLatfirst"); - //Serial.println(_lat * rad2DegInt); - setLat_degInt(_lat*rad2DegInt); - } + void setLat(float _lat) { + //Serial.print("setLatfirst"); + //Serial.println(_lat * rad2DegInt); + setLat_degInt(_lat*rad2DegInt); + } - float getLon() const { - return _lon_degInt * degInt2Rad; - } + float getLon() const { + return _lon_degInt * degInt2Rad; + } - void setLon(float _lon) { - this->_lon_degInt = _lon * rad2DegInt; - } + void setLon(float _lon) { + this->_lon_degInt = _lon * rad2DegInt; + } - float getVD() const { - return _vD; - } + float getVD() const { + return _vD; + } - float getVE() const { - return sin(getYaw()) * getGroundSpeed(); - } + float getVE() const { + return sin(getYaw()) * getGroundSpeed(); + } - float getGroundSpeed() const { - return _groundSpeed; - } + float getGroundSpeed() const { + return _groundSpeed; + } - int32_t getLat_degInt() const { - //Serial.print("getLat_degInt"); - //Serial.println(_lat_degInt); - return _lat_degInt; + int32_t getLat_degInt() const { + //Serial.print("getLat_degInt"); + //Serial.println(_lat_degInt); + return _lat_degInt; - } + } - int32_t getLon_degInt() const { - return _lon_degInt; - } + int32_t getLon_degInt() const { + return _lon_degInt; + } - float getVN() const { - return cos(getYaw()) * getGroundSpeed(); - } + float getVN() const { + return cos(getYaw()) * getGroundSpeed(); + } - float getPitch() const { - return _pitch; - } + float getPitch() const { + return _pitch; + } - float getPitchRate() const { - return _pitchRate; - } + float getPitchRate() const { + return _pitchRate; + } - float getRoll() const { - return _roll; - } + float getRoll() const { + return _roll; + } - float getRollRate() const { - return _rollRate; - } + float getRollRate() const { + return _rollRate; + } - float getYaw() const { - return _yaw; - } + float getYaw() const { + return _yaw; + } - float getYawRate() const { - return _yawRate; - } + float getYawRate() const { + return _yawRate; + } - void setAirSpeed(float airSpeed) { - _airSpeed = airSpeed; - } + void setAirSpeed(float airSpeed) { + _airSpeed = airSpeed; + } - void setAlt_intM(int32_t alt_intM) { - _alt_intM = alt_intM; - } + void setAlt_intM(int32_t alt_intM) { + _alt_intM = alt_intM; + } - void setVD(float vD) { - _vD = vD; - } + void setVD(float vD) { + _vD = vD; + } - void setGroundSpeed(float groundSpeed) { - _groundSpeed = groundSpeed; - } + void setGroundSpeed(float groundSpeed) { + _groundSpeed = groundSpeed; + } - void setLat_degInt(int32_t lat_degInt) { - _lat_degInt = lat_degInt; - //Serial.print("setLat_degInt"); - //Serial.println(_lat_degInt); - } + void setLat_degInt(int32_t lat_degInt) { + _lat_degInt = lat_degInt; + //Serial.print("setLat_degInt"); + //Serial.println(_lat_degInt); + } - void setLon_degInt(int32_t lon_degInt) { - _lon_degInt = lon_degInt; - } + void setLon_degInt(int32_t lon_degInt) { + _lon_degInt = lon_degInt; + } - void setPitch(float pitch) { - _pitch = pitch; - } + void setPitch(float pitch) { + _pitch = pitch; + } - void setPitchRate(float pitchRate) { - _pitchRate = pitchRate; - } + void setPitchRate(float pitchRate) { + _pitchRate = pitchRate; + } - void setRoll(float roll) { - _roll = roll; - } + void setRoll(float roll) { + _roll = roll; + } - void setRollRate(float rollRate) { - _rollRate = rollRate; - } + void setRollRate(float rollRate) { + _rollRate = rollRate; + } - void setYaw(float yaw) { - _yaw = yaw; - } + void setYaw(float yaw) { + _yaw = yaw; + } - void setYawRate(float yawRate) { - _yawRate = yawRate; - } - void setTimeStamp(int32_t timeStamp) { - _timeStamp = timeStamp; - } - int32_t getTimeStamp() const { - return _timeStamp; - } + void setYawRate(float yawRate) { + _yawRate = yawRate; + } + void setTimeStamp(int32_t timeStamp) { + _timeStamp = timeStamp; + } + int32_t getTimeStamp() const { + return _timeStamp; + } protected: - AP_HardwareAbstractionLayer * _hal; + AP_HardwareAbstractionLayer * _hal; private: - int32_t _timeStamp; // micros clock - float _roll; // rad - float _rollRate; //rad/s - float _pitch; // rad - float _pitchRate; // rad/s - float _yaw; // rad - float _yawRate; // rad/s - float _airSpeed; // m/s - float _groundSpeed; // m/s - float _vD; // m/s - int32_t _lat_degInt; // deg / 1e7 - int32_t _lon_degInt; // deg / 1e7 - int32_t _alt_intM; // meters / 1e3 + int32_t _timeStamp; // micros clock + float _roll; // rad + float _rollRate; //rad/s + float _pitch; // rad + float _pitchRate; // rad/s + float _yaw; // rad + float _yawRate; // rad/s + float _airSpeed; // m/s + float _groundSpeed; // m/s + float _vD; // m/s + int32_t _lat_degInt; // deg / 1e7 + int32_t _lon_degInt; // deg / 1e7 + int32_t _alt_intM; // meters / 1e3 }; class DcmNavigator: public AP_Navigator { private: - /** - * Sensors - */ + /** + * Sensors + */ - RangeFinder * _rangeFinderDown; - AP_DCM * _dcm; - IMU * _imu; - uint16_t _imuOffsetAddress; + RangeFinder * _rangeFinderDown; + AP_DCM * _dcm; + IMU * _imu; + uint16_t _imuOffsetAddress; public: - DcmNavigator(AP_HardwareAbstractionLayer * hal); - virtual void calibrate(); - virtual void updateFast(float dt); - virtual void updateSlow(float dt); - void updateGpsLight(void); + DcmNavigator(AP_HardwareAbstractionLayer * hal); + virtual void calibrate(); + virtual void updateFast(float dt); + virtual void updateSlow(float dt); + void updateGpsLight(void); }; } // namespace apo diff --git a/libraries/APO/AP_RcChannel.cpp b/libraries/APO/AP_RcChannel.cpp index 1c1f823482..1a88f887ce 100644 --- a/libraries/APO/AP_RcChannel.cpp +++ b/libraries/APO/AP_RcChannel.cpp @@ -18,85 +18,86 @@ namespace apo { AP_RcChannel::AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, - APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin, - const uint16_t & pwmNeutral, const uint16_t & pwmMax, - const rcMode_t & rcMode, const bool & reverse, const float & scale) : - AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")), - _pwmMin(this, 2, pwmMin, PSTR("pMin")), - _pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")), - _pwmMax(this, 4, pwmMax, PSTR("pMax")), - _reverse(this, 5, reverse, PSTR("rev")), - _scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))), - _rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) { - //Serial.print("pwm after ctor: "); Serial.println(pwmNeutral); - if (rcMode == RC_MODE_IN) - return; - //Serial.print("pwm set for ch: "); Serial.println(int(ch)); - rc.OutputCh(ch, pwmNeutral); + APM_RC_Class & rc, const uint8_t & ch, const uint16_t & pwmMin, + const uint16_t & pwmNeutral, const uint16_t & pwmMax, + const rcMode_t & rcMode, const bool & reverse, const float & scale) : + AP_Var_group(keyValue, name), _ch(this, 1, ch, PSTR("ch")), + _pwmMin(this, 2, pwmMin, PSTR("pMin")), + _pwmNeutral(this, 3, pwmNeutral, PSTR("pNtrl")), + _pwmMax(this, 4, pwmMax, PSTR("pMax")), + _reverse(this, 5, reverse, PSTR("rev")), + _scale(scale == 0 ? AP_Float(0) : AP_Float(this,6,reverse,PSTR("scale"))), + _rcMode(rcMode), _rc(rc), _pwm(pwmNeutral) { + //Serial.print("pwm after ctor: "); Serial.println(pwmNeutral); + if (rcMode == RC_MODE_IN) + return; + //Serial.print("pwm set for ch: "); Serial.println(int(ch)); + rc.OutputCh(ch, pwmNeutral); } uint16_t AP_RcChannel::getRadioPwm() { - if (_rcMode == RC_MODE_OUT) { - Serial.print("tryng to read from output channel: "); - Serial.println(int(_ch)); - return _pwmNeutral; // if this happens give a safe value of neutral - } - return _rc.InputCh(_ch); + if (_rcMode == RC_MODE_OUT) { + Serial.print("tryng to read from output channel: "); + Serial.println(int(_ch)); + return _pwmNeutral; // if this happens give a safe value of neutral + } + return _rc.InputCh(_ch); } void AP_RcChannel::setPwm(uint16_t pwm) { - //Serial.printf("pwm in setPwm: %d\n", pwm); - //Serial.printf("reverse: %s\n", (reverse)?"true":"false"); + //Serial.printf("pwm in setPwm: %d\n", pwm); + //Serial.printf("reverse: %s\n", (reverse)?"true":"false"); - // apply reverse - if (_reverse) - pwm = int16_t(_pwmNeutral - pwm) + _pwmNeutral; - //Serial.printf("pwm after reverse: %d\n", pwm); + // apply reverse + if (_reverse) + pwm = int16_t(_pwmNeutral - pwm) + _pwmNeutral; + //Serial.printf("pwm after reverse: %d\n", pwm); - // apply saturation - if (_pwm > uint8_t(_pwmMax)) - _pwm = _pwmMax; - if (_pwm < uint8_t(_pwmMin)) - _pwm = _pwmMin; - _pwm = pwm; + // apply saturation + if (_pwm > uint8_t(_pwmMax)) + _pwm = _pwmMax; + if (_pwm < uint8_t(_pwmMin)) + _pwm = _pwmMin; + _pwm = pwm; - //Serial.print("ch: "); Serial.print(ch); Serial.print(" pwm: "); Serial.println(pwm); - if (_rcMode == RC_MODE_IN) - return; - _rc.OutputCh(_ch, _pwm); + //Serial.print("ch: "); Serial.print(ch); Serial.print(" pwm: "); Serial.println(pwm); + if (_rcMode == RC_MODE_IN) + return; + _rc.OutputCh(_ch, _pwm); } uint16_t AP_RcChannel::_positionToPwm(const float & position) { - uint16_t pwm; - //Serial.printf("position: %f\n", position); - if (position < 0) - pwm = position * int16_t(_pwmNeutral - _pwmMin) + _pwmNeutral; - else - pwm = position * int16_t(_pwmMax - _pwmNeutral) + _pwmNeutral; + uint16_t pwm; + //Serial.printf("position: %f\n", position); + if (position < 0) + pwm = position * int16_t(_pwmNeutral - _pwmMin) + _pwmNeutral; + else + pwm = position * int16_t(_pwmMax - _pwmNeutral) + _pwmNeutral; - if (pwm > uint16_t(_pwmMax)) - pwm = _pwmMax; - if (pwm < uint16_t(_pwmMin)) - pwm = _pwmMin; - return pwm; + if (pwm > uint16_t(_pwmMax)) + pwm = _pwmMax; + if (pwm < uint16_t(_pwmMin)) + pwm = _pwmMin; + return pwm; } float AP_RcChannel::_pwmToPosition(const uint16_t & pwm) { - float position; - // note a piece-wise linear mapping occurs if the pwm ranges - // are not symmetric about pwmNeutral - if (pwm < uint8_t(_pwmNeutral)) - position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( - _pwmNeutral - _pwmMin); - else - position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( - _pwmMax - _pwmNeutral); - if (position > 1) - position = 1; - if (position < -1) - position = -1; - return position; + float position; + // note a piece-wise linear mapping occurs if the pwm ranges + // are not symmetric about pwmNeutral + if (pwm < uint8_t(_pwmNeutral)) + position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( + _pwmNeutral - _pwmMin); + else + position = 1.0 * int16_t(pwm - _pwmNeutral) / int16_t( + _pwmMax - _pwmNeutral); + if (position > 1) + position = 1; + if (position < -1) + position = -1; + return position; } } // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_RcChannel.h b/libraries/APO/AP_RcChannel.h index 1a93132863..38cc05df9a 100644 --- a/libraries/APO/AP_RcChannel.h +++ b/libraries/APO/AP_RcChannel.h @@ -14,7 +14,7 @@ namespace apo { enum rcMode_t { - RC_MODE_IN, RC_MODE_OUT, RC_MODE_INOUT + RC_MODE_IN, RC_MODE_OUT, RC_MODE_INOUT }; /// @class AP_RcChannel @@ -23,62 +23,63 @@ class AP_RcChannel: public AP_Var_group { public: - /// Constructor - AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc, - const uint8_t & ch, const uint16_t & pwmMin, - const uint16_t & pwmNeutral, const uint16_t & pwmMax, - const rcMode_t & rcMode, - const bool & reverse, const float & scale = 0); + /// Constructor + AP_RcChannel(AP_Var::Key keyValue, const prog_char_t * name, APM_RC_Class & rc, + const uint8_t & ch, const uint16_t & pwmMin, + const uint16_t & pwmNeutral, const uint16_t & pwmMax, + const rcMode_t & rcMode, + const bool & reverse, const float & scale = 0); - // configuration - AP_Uint8 _ch; - AP_Uint16 _pwmMin; - AP_Uint16 _pwmNeutral; - AP_Uint16 _pwmMax; - rcMode_t _rcMode; - AP_Bool _reverse; - AP_Float _scale; + // configuration + AP_Uint8 _ch; + AP_Uint16 _pwmMin; + AP_Uint16 _pwmNeutral; + AP_Uint16 _pwmMax; + rcMode_t _rcMode; + AP_Bool _reverse; + AP_Float _scale; - // get - uint16_t getPwm() { - return _pwm; - } - uint16_t getRadioPwm(); - float getPosition() { - return _pwmToPosition(getPwm()); - } - float getRadioPosition() { - return _pwmToPosition(getRadioPwm()); - } - float getScaled() { - return _scale*getPwm(); - } + // get + uint16_t getPwm() { + return _pwm; + } + uint16_t getRadioPwm(); + float getPosition() { + return _pwmToPosition(getPwm()); + } + float getRadioPosition() { + return _pwmToPosition(getRadioPwm()); + } + float getScaled() { + return _scale*getPwm(); + } + + // set + void setUsingRadio() { + if (_rcMode != RC_MODE_OUT) setPwm(getRadioPwm()); + } + void setPwm(uint16_t pwm); + void setPosition(float position) { + setPwm(_positionToPwm(position)); + } + void setScaled(float val) { + setPwm(val/_scale); + } - // set - void setUsingRadio() { - if (_rcMode != RC_MODE_OUT) setPwm(getRadioPwm()); - } - void setPwm(uint16_t pwm); - void setPosition(float position) { - setPwm(_positionToPwm(position)); - } - void setScaled(float val) { - setPwm(val/_scale); - } - protected: - // configuration - APM_RC_Class & _rc; + // configuration + APM_RC_Class & _rc; - // internal states - uint16_t _pwm; // this is the internal state, position is just created when needed + // internal states + uint16_t _pwm; // this is the internal state, position is just created when needed - // private methods - uint16_t _positionToPwm(const float & position); - float _pwmToPosition(const uint16_t & pwm); + // private methods + uint16_t _positionToPwm(const float & position); + float _pwmToPosition(const uint16_t & pwm); }; } // apo #endif // AP_RCCHANNEL_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Var_keys.h b/libraries/APO/AP_Var_keys.h index 58a715b591..40ebf99620 100644 --- a/libraries/APO/AP_Var_keys.h +++ b/libraries/APO/AP_Var_keys.h @@ -3,22 +3,23 @@ enum keys { - // general - k_config = 0, - k_cntrl, - k_guide, - k_sensorCalib, + // general + k_config = 0, + k_cntrl, + k_guide, + k_sensorCalib, - k_radioChannelsStart=10, + k_radioChannelsStart=10, - k_controllersStart=30, + k_controllersStart=30, - k_customStart=100, + k_customStart=100, - // 200-256 reserved for commands - k_commands = 200 + // 200-256 reserved for commands + k_commands = 200 }; // max 256 keys #endif +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/constants.h b/libraries/APO/constants.h index 2a4316bcb3..27f03c50b8 100644 --- a/libraries/APO/constants.h +++ b/libraries/APO/constants.h @@ -21,3 +21,4 @@ const float degInt2Rad = deg2Rad / scale_deg; // degrees x 1e7 to radians #define MAV_MODE_FAILSAFE MAV_MODE_TEST3 #endif /* CONSTANTS_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/examples/MavlinkTest/MavlinkTest.pde b/libraries/APO/examples/MavlinkTest/MavlinkTest.pde index d64be33822..f45cd2e510 100644 --- a/libraries/APO/examples/MavlinkTest/MavlinkTest.pde +++ b/libraries/APO/examples/MavlinkTest/MavlinkTest.pde @@ -1,7 +1,7 @@ /* AnalogReadSerial - Reads an analog input on pin 0, prints the result to the serial monitor - + Reads an analog input on pin 0, prints the result to the serial monitor + This example code is in the public domain. */ @@ -10,40 +10,40 @@ int packetDrops = 0; void handleMessage(mavlink_message_t * msg) { - Serial.print(", received mavlink message: "); - Serial.print(msg->msgid, DEC); + Serial.print(", received mavlink message: "); + Serial.print(msg->msgid, DEC); } void setup() { - Serial.begin(57600); - Serial3.begin(57600); - mavlink_comm_0_port = &Serial3; - packetDrops = 0; + Serial.begin(57600); + Serial3.begin(57600); + mavlink_comm_0_port = &Serial3; + packetDrops = 0; } void loop() { - mavlink_msg_heartbeat_send(MAVLINK_COMM_0, mavlink_system.type, - MAV_AUTOPILOT_ARDUPILOTMEGA); - Serial.print("heartbeat sent"); + mavlink_msg_heartbeat_send(MAVLINK_COMM_0, mavlink_system.type, + MAV_AUTOPILOT_ARDUPILOTMEGA); + Serial.print("heartbeat sent"); - // receive new packets - mavlink_message_t msg; - mavlink_status_t status; + // receive new packets + mavlink_message_t msg; + mavlink_status_t status; - Serial.print(", bytes available: "); - Serial.print(comm_get_available(MAVLINK_COMM_0)); - while (comm_get_available( MAVLINK_COMM_0)) { - uint8_t c = comm_receive_ch(MAVLINK_COMM_0); + Serial.print(", bytes available: "); + Serial.print(comm_get_available(MAVLINK_COMM_0)); + while (comm_get_available( MAVLINK_COMM_0)) { + uint8_t c = comm_receive_ch(MAVLINK_COMM_0); - // Try to get a new message - if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) - handleMessage(&msg); - } + // Try to get a new message + if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) + handleMessage(&msg); + } - // Update packet drops counter - packetDrops += status.packet_rx_drop_count; + // Update packet drops counter + packetDrops += status.packet_rx_drop_count; - Serial.print(", dropped packets: "); - Serial.println(packetDrops); - delay(1000); + Serial.print(", dropped packets: "); + Serial.println(packetDrops); + delay(1000); } diff --git a/libraries/APO/examples/ServoManual/ServoManual.pde b/libraries/APO/examples/ServoManual/ServoManual.pde index 8be346f18a..d8abddc9ca 100644 --- a/libraries/APO/examples/ServoManual/ServoManual.pde +++ b/libraries/APO/examples/ServoManual/ServoManual.pde @@ -19,91 +19,91 @@ using namespace apo; class RadioTest { private: - float testPosition; - int8_t testSign; - enum { - version, - rollKey, - pitchKey, - thrKey, - yawKey, - ch5Key, - ch6Key, - ch7Key, - ch8Key - }; - Vector ch; + float testPosition; + int8_t testSign; + enum { + version, + rollKey, + pitchKey, + thrKey, + yawKey, + ch5Key, + ch6Key, + ch7Key, + ch8Key + }; + Vector ch; public: - RadioTest() : - testPosition(2), testSign(1) { - ch.push_back( - new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, - 1500, 1900)); - ch.push_back( - new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, - 1900)); + RadioTest() : + testPosition(2), testSign(1) { + ch.push_back( + new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, + 1500, 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, + 1900, RC_MODE_INOUT, false)); + ch.push_back( + new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, + 1900, RC_MODE_INOUT, false)); - Serial.begin(115200); - delay(2000); - Serial.println("ArduPilot RC Channel test"); - APM_RC.Init(); // APM Radio initialization - delay(2000); - } + Serial.begin(115200); + delay(2000); + Serial.println("ArduPilot RC Channel test"); + APM_RC.Init(); // APM Radio initialization + delay(2000); + } - void update() { - // read the radio - for (uint8_t i = 0; i < ch.getSize(); i++) - ch[i]->setUsingRadio(); + void update() { + // read the radio + for (uint8_t i = 0; i < ch.getSize(); i++) + ch[i]->setUsingRadio(); - // print channel names - Serial.print("\t\t"); - static char name[7]; - for (uint8_t i = 0; i < ch.getSize(); i++) { - ch[i]->copy_name(name, 7); - Serial.printf("%7s\t", name); - } - Serial.println(); + // print channel names + Serial.print("\t\t"); + static char name[7]; + for (uint8_t i = 0; i < ch.getSize(); i++) { + ch[i]->copy_name(name, 7); + Serial.printf("%7s\t", name); + } + Serial.println(); - // print pwm - Serial.printf("pwm :\t"); - for (uint8_t i = 0; i < ch.getSize(); i++) - Serial.printf("%7d\t", ch[i]->getPwm()); - Serial.println(); + // print pwm + Serial.printf("pwm :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7d\t", ch[i]->getPwm()); + Serial.println(); - // print position - Serial.printf("position :\t"); - for (uint8_t i = 0; i < ch.getSize(); i++) - Serial.printf("%7.2f\t", ch[i]->getPosition()); - Serial.println(); + // print position + Serial.printf("position :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7.2f\t", ch[i]->getPosition()); + Serial.println(); - delay(500); - } + delay(500); + } }; RadioTest * test; void setup() { - test = new RadioTest; + test = new RadioTest; } void loop() { - test->update(); + test->update(); } diff --git a/libraries/APO/examples/ServoSweep/ServoSweep.pde b/libraries/APO/examples/ServoSweep/ServoSweep.pde index 75827d4f09..fa6f7b746e 100644 --- a/libraries/APO/examples/ServoSweep/ServoSweep.pde +++ b/libraries/APO/examples/ServoSweep/ServoSweep.pde @@ -19,107 +19,107 @@ using namespace apo; class RadioTest { private: - float testPosition; - int8_t testSign; - enum { - version, - rollKey, - pitchKey, - thrKey, - yawKey, - ch5Key, - ch6Key, - ch7Key, - ch8Key - }; - Vector ch; + float testPosition; + int8_t testSign; + enum { + version, + rollKey, + pitchKey, + thrKey, + yawKey, + ch5Key, + ch6Key, + ch7Key, + ch8Key + }; + Vector ch; public: - RadioTest() : - testPosition(2), testSign(1) { - ch.push_back( - new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, - 1500, 1900)); - ch.push_back( - new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, - 1900)); - ch.push_back( - new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, - 1900)); + RadioTest() : + testPosition(2), testSign(1) { + ch.push_back( + new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, + 1500, 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, + 1900,RC_MODE_INOUT,false)); + ch.push_back( + new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, + 1900,RC_MODE_INOUT,false)); - Serial.begin(115200); - delay(2000); - Serial.println("ArduPilot RC Channel test"); - APM_RC.Init(); // APM Radio initialization - delay(2000); - } + Serial.begin(115200); + delay(2000); + Serial.println("ArduPilot RC Channel test"); + APM_RC.Init(); // APM Radio initialization + delay(2000); + } - void update() { - // update test value - testPosition += testSign * .1; - if (testPosition > 1) { - //eepromRegistry.print(Serial); // show eeprom map - testPosition = 1; - testSign = -1; - } else if (testPosition < -1) { - testPosition = -1; - testSign = 1; - } + void update() { + // update test value + testPosition += testSign * .1; + if (testPosition > 1) { + //eepromRegistry.print(Serial); // show eeprom map + testPosition = 1; + testSign = -1; + } else if (testPosition < -1) { + testPosition = -1; + testSign = 1; + } - // set channel positions - for (uint8_t i = 0; i < ch.getSize(); i++) - ch[i]->setPosition(testPosition); + // set channel positions + for (uint8_t i = 0; i < ch.getSize(); i++) + ch[i]->setPosition(testPosition); - // print test position - Serial.printf("\nnormalized position (%f)\n", testPosition); + // print test position + Serial.printf("\nnormalized position (%f)\n", testPosition); - // print channel names - Serial.print("\t\t"); - static char name[7]; - for (uint8_t i = 0; i < ch.getSize(); i++) { - ch[i]->copy_name(name, 7); - Serial.printf("%7s\t", name); - } - Serial.println(); + // print channel names + Serial.print("\t\t"); + static char name[7]; + for (uint8_t i = 0; i < ch.getSize(); i++) { + ch[i]->copy_name(name, 7); + Serial.printf("%7s\t", name); + } + Serial.println(); - // print pwm - Serial.printf("pwm :\t"); - for (uint8_t i = 0; i < ch.getSize(); i++) - Serial.printf("%7d\t", ch[i]->getRadioPwm()); - Serial.println(); + // print pwm + Serial.printf("pwm :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7d\t", ch[i]->getRadioPwm()); + Serial.println(); - // print position - Serial.printf("position :\t"); - for (uint8_t i = 0; i < ch.getSize(); i++) - Serial.printf("%7.2f\t", ch[i]->getRadioPosition()); - Serial.println(); + // print position + Serial.printf("position :\t"); + for (uint8_t i = 0; i < ch.getSize(); i++) + Serial.printf("%7.2f\t", ch[i]->getRadioPosition()); + Serial.println(); - delay(500); - } + delay(500); + } }; RadioTest * test; void setup() { - test = new RadioTest; + test = new RadioTest; } void loop() { - test->update(); + test->update(); } // vim:ts=4:sw=4:expandtab diff --git a/libraries/Desktop/Desktop.mk b/libraries/Desktop/Desktop.mk index 63ac2a7284..b5bc8732ce 100644 --- a/libraries/Desktop/Desktop.mk +++ b/libraries/Desktop/Desktop.mk @@ -171,7 +171,7 @@ else endif # these are library objects we don't want in the desktop build (maybe we'll add them later) -NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp RC_Channel/RC_Channel_aux.cpp +NODESKTOP := FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp # # Find sketchbook libraries referenced by the sketch. diff --git a/libraries/Desktop/Makefile.desktop b/libraries/Desktop/Makefile.desktop index 2449a8b256..31d922b92f 100644 --- a/libraries/Desktop/Makefile.desktop +++ b/libraries/Desktop/Makefile.desktop @@ -25,3 +25,6 @@ heli: helihil: make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME -DHIL_MODE=HIL_MODE_ATTITUDE -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED" + +mavlink10: + make -f $(DESKTOP)/Makefile.desktop EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED" diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index ea90e307fd..bbf3cf4412 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -11,7 +11,11 @@ BetterStream *mavlink_comm_1_port; // this might need to move to the flight software mavlink_system_t mavlink_system = {7,1,0,0}; -#include "include/mavlink_helpers.h" +#ifdef MAVLINK10 +# include "include_v1.0/mavlink_helpers.h" +#else +# include "include/mavlink_helpers.h" +#endif uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid) { diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 5d80f46288..4b3a038e0b 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -10,13 +10,21 @@ #define MAVLINK_SEPARATE_HELPERS -#include "include/ardupilotmega/version.h" +#ifdef MAVLINK10 +# include "include_v1.0/ardupilotmega/version.h" +#else +# include "include/ardupilotmega/version.h" +#endif // this allows us to make mavlink_message_t much smaller #define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE #define MAVLINK_COMM_NUM_BUFFERS 2 -#include "include/mavlink_types.h" +#ifdef MAVLINK10 +# include "include_v1.0/mavlink_types.h" +#else +# include "include/mavlink_types.h" +#endif /// MAVLink stream used for HIL interaction extern BetterStream *mavlink_comm_0_port; @@ -109,7 +117,11 @@ static inline int comm_get_txspace(mavlink_channel_t chan) } #define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#include "include/ardupilotmega/mavlink.h" +#ifdef MAVLINK10 +# include "include_v1.0/ardupilotmega/mavlink.h" +#else +# include "include/ardupilotmega/mavlink.h" +#endif uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid); diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h index 1272728607..e650159666 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h @@ -12,15 +12,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} +#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} +#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {NULL}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG} #endif #include "../protocol.h" @@ -48,6 +48,7 @@ extern "C" { #include "./mavlink_msg_sensor_offsets.h" #include "./mavlink_msg_set_mag_offsets.h" #include "./mavlink_msg_meminfo.h" +#include "./mavlink_msg_ap_adc.h" #ifdef __cplusplus } diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h new file mode 100644 index 0000000000..d42edb15d3 --- /dev/null +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_adc.h @@ -0,0 +1,254 @@ +// MESSAGE AP_ADC PACKING + +#define MAVLINK_MSG_ID_AP_ADC 153 + +typedef struct __mavlink_ap_adc_t +{ + uint16_t adc1; ///< ADC output 1 + uint16_t adc2; ///< ADC output 2 + uint16_t adc3; ///< ADC output 3 + uint16_t adc4; ///< ADC output 4 + uint16_t adc5; ///< ADC output 5 + uint16_t adc6; ///< ADC output 6 +} mavlink_ap_adc_t; + +#define MAVLINK_MSG_ID_AP_ADC_LEN 12 +#define MAVLINK_MSG_ID_153_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_AP_ADC { \ + "AP_ADC", \ + 6, \ + { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \ + { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \ + { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \ + { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \ + { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \ + { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \ + } \ +} + + +/** + * @brief Pack a ap_adc message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message(msg, system_id, component_id, 12); +} + +/** + * @brief Pack a ap_adc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12); +} + +/** + * @brief Encode a ap_adc struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ap_adc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) +{ + return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); +} + +/** + * @brief Send a ap_adc message + * @param chan MAVLink channel to send the message + * + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12); +#endif +} + +#endif + +// MESSAGE AP_ADC UNPACKING + + +/** + * @brief Get field adc1 from ap_adc message + * + * @return ADC output 1 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field adc2 from ap_adc message + * + * @return ADC output 2 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field adc3 from ap_adc message + * + * @return ADC output 3 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field adc4 from ap_adc message + * + * @return ADC output 4 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field adc5 from ap_adc message + * + * @return ADC output 5 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field adc6 from ap_adc message + * + * @return ADC output 6 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Decode a ap_adc message into a struct + * + * @param msg The message to decode + * @param ap_adc C-struct to decode the message contents into + */ +static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc) +{ +#if MAVLINK_NEED_BYTE_SWAP + ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg); + ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg); + ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg); + ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg); + ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); + ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); +#else + memcpy(ap_adc, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_timing.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_timing.h new file mode 100644 index 0000000000..cc71f71bfa --- /dev/null +++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_ap_timing.h @@ -0,0 +1,210 @@ +// MESSAGE AP_TIMING PACKING + +#define MAVLINK_MSG_ID_AP_TIMING 155 + +typedef struct __mavlink_ap_timing_t +{ + uint16_t min_50Hz_delta; ///< mininum delta for 50Hz loop + uint16_t max_50Hz_delta; ///< maximum delta for 50Hz loop + uint16_t min_200Hz_delta; ///< mininum delta for 200Hz loop + uint16_t max_200Hz_delta; ///< maximum delta for 200Hz loop +} mavlink_ap_timing_t; + +#define MAVLINK_MSG_ID_AP_TIMING_LEN 8 +#define MAVLINK_MSG_ID_155_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_AP_TIMING { \ + "AP_TIMING", \ + 4, \ + { { "min_50Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_timing_t, min_50Hz_delta) }, \ + { "max_50Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_timing_t, max_50Hz_delta) }, \ + { "min_200Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_timing_t, min_200Hz_delta) }, \ + { "max_200Hz_delta", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_timing_t, max_200Hz_delta) }, \ + } \ +} + + +/** + * @brief Pack a ap_timing message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param min_50Hz_delta mininum delta for 50Hz loop + * @param max_50Hz_delta maximum delta for 50Hz loop + * @param min_200Hz_delta mininum delta for 200Hz loop + * @param max_200Hz_delta maximum delta for 200Hz loop + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_timing_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t min_50Hz_delta, uint16_t max_50Hz_delta, uint16_t min_200Hz_delta, uint16_t max_200Hz_delta) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint16_t(buf, 0, min_50Hz_delta); + _mav_put_uint16_t(buf, 2, max_50Hz_delta); + _mav_put_uint16_t(buf, 4, min_200Hz_delta); + _mav_put_uint16_t(buf, 6, max_200Hz_delta); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_ap_timing_t packet; + packet.min_50Hz_delta = min_50Hz_delta; + packet.max_50Hz_delta = max_50Hz_delta; + packet.min_200Hz_delta = min_200Hz_delta; + packet.max_200Hz_delta = max_200Hz_delta; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_TIMING; + return mavlink_finalize_message(msg, system_id, component_id, 8); +} + +/** + * @brief Pack a ap_timing message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param min_50Hz_delta mininum delta for 50Hz loop + * @param max_50Hz_delta maximum delta for 50Hz loop + * @param min_200Hz_delta mininum delta for 200Hz loop + * @param max_200Hz_delta maximum delta for 200Hz loop + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_timing_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t min_50Hz_delta,uint16_t max_50Hz_delta,uint16_t min_200Hz_delta,uint16_t max_200Hz_delta) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint16_t(buf, 0, min_50Hz_delta); + _mav_put_uint16_t(buf, 2, max_50Hz_delta); + _mav_put_uint16_t(buf, 4, min_200Hz_delta); + _mav_put_uint16_t(buf, 6, max_200Hz_delta); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_ap_timing_t packet; + packet.min_50Hz_delta = min_50Hz_delta; + packet.max_50Hz_delta = max_50Hz_delta; + packet.min_200Hz_delta = min_200Hz_delta; + packet.max_200Hz_delta = max_200Hz_delta; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_TIMING; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8); +} + +/** + * @brief Encode a ap_timing struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ap_timing C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ap_timing_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_timing_t* ap_timing) +{ + return mavlink_msg_ap_timing_pack(system_id, component_id, msg, ap_timing->min_50Hz_delta, ap_timing->max_50Hz_delta, ap_timing->min_200Hz_delta, ap_timing->max_200Hz_delta); +} + +/** + * @brief Send a ap_timing message + * @param chan MAVLink channel to send the message + * + * @param min_50Hz_delta mininum delta for 50Hz loop + * @param max_50Hz_delta maximum delta for 50Hz loop + * @param min_200Hz_delta mininum delta for 200Hz loop + * @param max_200Hz_delta maximum delta for 200Hz loop + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ap_timing_send(mavlink_channel_t chan, uint16_t min_50Hz_delta, uint16_t max_50Hz_delta, uint16_t min_200Hz_delta, uint16_t max_200Hz_delta) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint16_t(buf, 0, min_50Hz_delta); + _mav_put_uint16_t(buf, 2, max_50Hz_delta); + _mav_put_uint16_t(buf, 4, min_200Hz_delta); + _mav_put_uint16_t(buf, 6, max_200Hz_delta); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_TIMING, buf, 8); +#else + mavlink_ap_timing_t packet; + packet.min_50Hz_delta = min_50Hz_delta; + packet.max_50Hz_delta = max_50Hz_delta; + packet.min_200Hz_delta = min_200Hz_delta; + packet.max_200Hz_delta = max_200Hz_delta; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_TIMING, (const char *)&packet, 8); +#endif +} + +#endif + +// MESSAGE AP_TIMING UNPACKING + + +/** + * @brief Get field min_50Hz_delta from ap_timing message + * + * @return mininum delta for 50Hz loop + */ +static inline uint16_t mavlink_msg_ap_timing_get_min_50Hz_delta(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field max_50Hz_delta from ap_timing message + * + * @return maximum delta for 50Hz loop + */ +static inline uint16_t mavlink_msg_ap_timing_get_max_50Hz_delta(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field min_200Hz_delta from ap_timing message + * + * @return mininum delta for 200Hz loop + */ +static inline uint16_t mavlink_msg_ap_timing_get_min_200Hz_delta(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field max_200Hz_delta from ap_timing message + * + * @return maximum delta for 200Hz loop + */ +static inline uint16_t mavlink_msg_ap_timing_get_max_200Hz_delta(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a ap_timing message into a struct + * + * @param msg The message to decode + * @param ap_timing C-struct to decode the message contents into + */ +static inline void mavlink_msg_ap_timing_decode(const mavlink_message_t* msg, mavlink_ap_timing_t* ap_timing) +{ +#if MAVLINK_NEED_BYTE_SWAP + ap_timing->min_50Hz_delta = mavlink_msg_ap_timing_get_min_50Hz_delta(msg); + ap_timing->max_50Hz_delta = mavlink_msg_ap_timing_get_max_50Hz_delta(msg); + ap_timing->min_200Hz_delta = mavlink_msg_ap_timing_get_min_200Hz_delta(msg); + ap_timing->max_200Hz_delta = mavlink_msg_ap_timing_get_max_200Hz_delta(msg); +#else + memcpy(ap_timing, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h index cd59317f8f..6b7ebfe000 100644 --- a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h +++ b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h @@ -185,11 +185,65 @@ static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlin MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_ap_adc_t packet_in = { + 17235, + 17339, + 17443, + 17547, + 17651, + 17755, + }; + mavlink_ap_adc_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.adc1 = packet_in.adc1; + packet1.adc2 = packet_in.adc2; + packet1.adc3 = packet_in.adc3; + packet1.adc4 = packet_in.adc4; + packet1.adc5 = packet_in.adc5; + packet1.adc6 = packet_in.adc6; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_ap_adc_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 ); + mavlink_msg_ap_adc_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 ); + mavlink_msg_ap_adc_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message(msg, system_id, component_id, 12, 188); +} + +/** + * @brief Pack a ap_adc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_AP_ADC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188); +} + +/** + * @brief Encode a ap_adc struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ap_adc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) +{ + return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); +} + +/** + * @brief Send a ap_adc message + * @param chan MAVLink channel to send the message + * + * @param adc1 ADC output 1 + * @param adc2 ADC output 2 + * @param adc3 ADC output 3 + * @param adc4 ADC output 4 + * @param adc5 ADC output 5 + * @param adc6 ADC output 6 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint16_t(buf, 0, adc1); + _mav_put_uint16_t(buf, 2, adc2); + _mav_put_uint16_t(buf, 4, adc3); + _mav_put_uint16_t(buf, 6, adc4); + _mav_put_uint16_t(buf, 8, adc5); + _mav_put_uint16_t(buf, 10, adc6); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188); +#else + mavlink_ap_adc_t packet; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.adc5 = adc5; + packet.adc6 = adc6; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188); +#endif +} + +#endif + +// MESSAGE AP_ADC UNPACKING + + +/** + * @brief Get field adc1 from ap_adc message + * + * @return ADC output 1 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field adc2 from ap_adc message + * + * @return ADC output 2 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field adc3 from ap_adc message + * + * @return ADC output 3 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field adc4 from ap_adc message + * + * @return ADC output 4 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field adc5 from ap_adc message + * + * @return ADC output 5 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field adc6 from ap_adc message + * + * @return ADC output 6 + */ +static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Decode a ap_adc message into a struct + * + * @param msg The message to decode + * @param ap_adc C-struct to decode the message contents into + */ +static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc) +{ +#if MAVLINK_NEED_BYTE_SWAP + ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg); + ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg); + ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg); + ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg); + ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); + ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); +#else + memcpy(ap_adc, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h new file mode 100644 index 0000000000..85b7d96fc8 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_meminfo.h @@ -0,0 +1,166 @@ +// MESSAGE MEMINFO PACKING + +#define MAVLINK_MSG_ID_MEMINFO 152 + +typedef struct __mavlink_meminfo_t +{ + uint16_t brkval; ///< heap top + uint16_t freemem; ///< free memory +} mavlink_meminfo_t; + +#define MAVLINK_MSG_ID_MEMINFO_LEN 4 +#define MAVLINK_MSG_ID_152_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MEMINFO { \ + "MEMINFO", \ + 2, \ + { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \ + { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \ + } \ +} + + +/** + * @brief Pack a meminfo message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param brkval heap top + * @param freemem free memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t brkval, uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMINFO; + return mavlink_finalize_message(msg, system_id, component_id, 4, 208); +} + +/** + * @brief Pack a meminfo message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param brkval heap top + * @param freemem free memory + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t brkval,uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMINFO; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208); +} + +/** + * @brief Encode a meminfo struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param meminfo C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo) +{ + return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem); +} + +/** + * @brief Send a meminfo message + * @param chan MAVLink channel to send the message + * + * @param brkval heap top + * @param freemem free memory + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, brkval); + _mav_put_uint16_t(buf, 2, freemem); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4, 208); +#else + mavlink_meminfo_t packet; + packet.brkval = brkval; + packet.freemem = freemem; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4, 208); +#endif +} + +#endif + +// MESSAGE MEMINFO UNPACKING + + +/** + * @brief Get field brkval from meminfo message + * + * @return heap top + */ +static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field freemem from meminfo message + * + * @return free memory + */ +static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a meminfo message into a struct + * + * @param msg The message to decode + * @param meminfo C-struct to decode the message contents into + */ +static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo) +{ +#if MAVLINK_NEED_BYTE_SWAP + meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg); + meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg); +#else + memcpy(meminfo, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h new file mode 100644 index 0000000000..b3b38e6df2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h @@ -0,0 +1,386 @@ +// MESSAGE SENSOR_OFFSETS PACKING + +#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150 + +typedef struct __mavlink_sensor_offsets_t +{ + float mag_declination; ///< magnetic declination (radians) + int32_t raw_press; ///< raw pressure from barometer + int32_t raw_temp; ///< raw temperature from barometer + float gyro_cal_x; ///< gyro X calibration + float gyro_cal_y; ///< gyro Y calibration + float gyro_cal_z; ///< gyro Z calibration + float accel_cal_x; ///< accel X calibration + float accel_cal_y; ///< accel Y calibration + float accel_cal_z; ///< accel Z calibration + int16_t mag_ofs_x; ///< magnetometer X offset + int16_t mag_ofs_y; ///< magnetometer Y offset + int16_t mag_ofs_z; ///< magnetometer Z offset +} mavlink_sensor_offsets_t; + +#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42 +#define MAVLINK_MSG_ID_150_LEN 42 + + + +#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \ + "SENSOR_OFFSETS", \ + 12, \ + { { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \ + { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \ + { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \ + { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \ + { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \ + { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \ + { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \ + { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \ + { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \ + { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \ + } \ +} + + +/** + * @brief Pack a sensor_offsets message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; + return mavlink_finalize_message(msg, system_id, component_id, 42, 134); +} + +/** + * @brief Pack a sensor_offsets message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 134); +} + +/** + * @brief Encode a sensor_offsets struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sensor_offsets C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets) +{ + return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z); +} + +/** + * @brief Send a sensor_offsets message + * @param chan MAVLink channel to send the message + * + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @param mag_declination magnetic declination (radians) + * @param raw_press raw pressure from barometer + * @param raw_temp raw temperature from barometer + * @param gyro_cal_x gyro X calibration + * @param gyro_cal_y gyro Y calibration + * @param gyro_cal_z gyro Z calibration + * @param accel_cal_x accel X calibration + * @param accel_cal_y accel Y calibration + * @param accel_cal_z accel Z calibration + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_float(buf, 0, mag_declination); + _mav_put_int32_t(buf, 4, raw_press); + _mav_put_int32_t(buf, 8, raw_temp); + _mav_put_float(buf, 12, gyro_cal_x); + _mav_put_float(buf, 16, gyro_cal_y); + _mav_put_float(buf, 20, gyro_cal_z); + _mav_put_float(buf, 24, accel_cal_x); + _mav_put_float(buf, 28, accel_cal_y); + _mav_put_float(buf, 32, accel_cal_z); + _mav_put_int16_t(buf, 36, mag_ofs_x); + _mav_put_int16_t(buf, 38, mag_ofs_y); + _mav_put_int16_t(buf, 40, mag_ofs_z); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, 42, 134); +#else + mavlink_sensor_offsets_t packet; + packet.mag_declination = mag_declination; + packet.raw_press = raw_press; + packet.raw_temp = raw_temp; + packet.gyro_cal_x = gyro_cal_x; + packet.gyro_cal_y = gyro_cal_y; + packet.gyro_cal_z = gyro_cal_z; + packet.accel_cal_x = accel_cal_x; + packet.accel_cal_y = accel_cal_y; + packet.accel_cal_z = accel_cal_z; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, 42, 134); +#endif +} + +#endif + +// MESSAGE SENSOR_OFFSETS UNPACKING + + +/** + * @brief Get field mag_ofs_x from sensor_offsets message + * + * @return magnetometer X offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 36); +} + +/** + * @brief Get field mag_ofs_y from sensor_offsets message + * + * @return magnetometer Y offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 38); +} + +/** + * @brief Get field mag_ofs_z from sensor_offsets message + * + * @return magnetometer Z offset + */ +static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 40); +} + +/** + * @brief Get field mag_declination from sensor_offsets message + * + * @return magnetic declination (radians) + */ +static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field raw_press from sensor_offsets message + * + * @return raw pressure from barometer + */ +static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field raw_temp from sensor_offsets message + * + * @return raw temperature from barometer + */ +static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field gyro_cal_x from sensor_offsets message + * + * @return gyro X calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field gyro_cal_y from sensor_offsets message + * + * @return gyro Y calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field gyro_cal_z from sensor_offsets message + * + * @return gyro Z calibration + */ +static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field accel_cal_x from sensor_offsets message + * + * @return accel X calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field accel_cal_y from sensor_offsets message + * + * @return accel Y calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field accel_cal_z from sensor_offsets message + * + * @return accel Z calibration + */ +static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a sensor_offsets message into a struct + * + * @param msg The message to decode + * @param sensor_offsets C-struct to decode the message contents into + */ +static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets) +{ +#if MAVLINK_NEED_BYTE_SWAP + sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg); + sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg); + sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg); + sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg); + sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg); + sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg); + sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg); + sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg); + sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg); + sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg); + sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg); + sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg); +#else + memcpy(sensor_offsets, _MAV_PAYLOAD(msg), 42); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h new file mode 100644 index 0000000000..0151161901 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h @@ -0,0 +1,232 @@ +// MESSAGE SET_MAG_OFFSETS PACKING + +#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151 + +typedef struct __mavlink_set_mag_offsets_t +{ + int16_t mag_ofs_x; ///< magnetometer X offset + int16_t mag_ofs_y; ///< magnetometer Y offset + int16_t mag_ofs_z; ///< magnetometer Z offset + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_mag_offsets_t; + +#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8 +#define MAVLINK_MSG_ID_151_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \ + "SET_MAG_OFFSETS", \ + 5, \ + { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \ + { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \ + { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_mag_offsets message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; + return mavlink_finalize_message(msg, system_id, component_id, 8, 219); +} + +/** + * @brief Pack a set_mag_offsets message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219); +} + +/** + * @brief Encode a set_mag_offsets struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_mag_offsets C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets) +{ + return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z); +} + +/** + * @brief Send a set_mag_offsets message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param mag_ofs_x magnetometer X offset + * @param mag_ofs_y magnetometer Y offset + * @param mag_ofs_z magnetometer Z offset + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_int16_t(buf, 0, mag_ofs_x); + _mav_put_int16_t(buf, 2, mag_ofs_y); + _mav_put_int16_t(buf, 4, mag_ofs_z); + _mav_put_uint8_t(buf, 6, target_system); + _mav_put_uint8_t(buf, 7, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8, 219); +#else + mavlink_set_mag_offsets_t packet; + packet.mag_ofs_x = mag_ofs_x; + packet.mag_ofs_y = mag_ofs_y; + packet.mag_ofs_z = mag_ofs_z; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8, 219); +#endif +} + +#endif + +// MESSAGE SET_MAG_OFFSETS UNPACKING + + +/** + * @brief Get field target_system from set_mag_offsets message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field target_component from set_mag_offsets message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mag_ofs_x from set_mag_offsets message + * + * @return magnetometer X offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Get field mag_ofs_y from set_mag_offsets message + * + * @return magnetometer Y offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 2); +} + +/** + * @brief Get field mag_ofs_z from set_mag_offsets message + * + * @return magnetometer Z offset + */ +static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Decode a set_mag_offsets message into a struct + * + * @param msg The message to decode + * @param set_mag_offsets C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg); + set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg); + set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg); + set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg); + set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg); +#else + memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h new file mode 100644 index 0000000000..c7cdc402f7 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h @@ -0,0 +1,252 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef ARDUPILOTMEGA_TESTSUITE_H +#define ARDUPILOTMEGA_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_ardupilotmega(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_sensor_offsets_t packet_in = { + 17.0, + 963497672, + 963497880, + 101.0, + 129.0, + 157.0, + 185.0, + 213.0, + 241.0, + 19107, + 19211, + 19315, + }; + mavlink_sensor_offsets_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.mag_declination = packet_in.mag_declination; + packet1.raw_press = packet_in.raw_press; + packet1.raw_temp = packet_in.raw_temp; + packet1.gyro_cal_x = packet_in.gyro_cal_x; + packet1.gyro_cal_y = packet_in.gyro_cal_y; + packet1.gyro_cal_z = packet_in.gyro_cal_z; + packet1.accel_cal_x = packet_in.accel_cal_x; + packet1.accel_cal_y = packet_in.accel_cal_y; + packet1.accel_cal_z = packet_in.accel_cal_z; + packet1.mag_ofs_x = packet_in.mag_ofs_x; + packet1.mag_ofs_y = packet_in.mag_ofs_y; + packet1.mag_ofs_z = packet_in.mag_ofs_z; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_sensor_offsets_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); + mavlink_msg_sensor_offsets_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); + mavlink_msg_sensor_offsets_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); +} + +/** + * @brief Initiliaze the buffer for the X.25 CRC + * + * @param crcAccum the 16 bit X.25 CRC + */ +static inline void crc_init(uint16_t* crcAccum) +{ + *crcAccum = X25_INIT_CRC; +} + + +/** + * @brief Calculates the X.25 checksum on a byte buffer + * + * @param pBuffer buffer containing the byte array to hash + * @param length length of the byte array + * @return the checksum over the buffer bytes + **/ +static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) +{ + uint16_t crcTmp; + crc_init(&crcTmp); + while (length--) { + crc_accumulate(*pBuffer++, &crcTmp); + } + return crcTmp; +} + +/** + * @brief Accumulate the X.25 CRC by adding an array of bytes + * + * The checksum function adds the hash of one char at a time to the + * 16 bit checksum (uint16_t). + * + * @param data new bytes to hash + * @param crcAccum the already accumulated checksum + **/ +static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) +{ + const uint8_t *p = (const uint8_t *)pBuffer; + while (length--) { + crc_accumulate(*p++, crcAccum); + } +} + + + + +#endif /* _CHECKSUM_H_ */ + +#ifdef __cplusplus +} +#endif diff --git a/libraries/GCS_MAVLink/include_v1.0/common/common.h b/libraries/GCS_MAVLink/include_v1.0/common/common.h new file mode 100644 index 0000000000..cde9b18141 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/common.h @@ -0,0 +1,424 @@ +/** @file + * @brief MAVLink comm protocol generated from common.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef COMMON_H +#define COMMON_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_COMMON + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// ENUM DEFINITIONS + + +/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ +enum MAV_AUTOPILOT +{ + MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ + MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ + MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ + MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ + MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ + MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ + MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ + MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ + MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ + MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ + MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ + MAV_AUTOPILOT_ENUM_END=12, /* | */ +}; + +/** @brief These flags encode the MAV mode. */ +enum MAV_MODE_FLAG +{ + MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ + MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ + MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ + MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ + MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ + MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ + MAV_MODE_FLAG_RESERVED_ENABLED=1, /* 0b00000001 Reserved for future use. | */ + MAV_MODE_FLAG_ENUM_END=129, /* | */ +}; + +/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ +enum MAV_MODE_FLAG_DECODE_POSITION +{ + MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ + MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ + MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ + MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ + MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ + MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ + MAV_MODE_FLAG_DECODE_POSITION_RESERVED=1, /* Eighth bit: 00000001 | */ + MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ +}; + +/** @brief Override command, pauses current mission execution and moves immediately to a position */ +enum MAV_GOTO +{ + MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ + MAV_GOTO_DO_CONTINUE=1, /* Continue with the mission execution. | */ + MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ + MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ + MAV_GOTO_ENUM_END=4, /* | */ +}; + +/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ +enum MAV_MODE +{ + MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ + MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ + MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ + MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ + MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ + MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ + MAV_MODE_ENUM_END=221, /* | */ +}; + +/** @brief */ +enum MAV_STATE +{ + MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ + MAV_STATE_BOOT=1, /* System is booting up. | */ + MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ + MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ + MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ + MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ + MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ + MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ + MAV_STATE_ENUM_END=8, /* | */ +}; + +/** @brief */ +enum MAV_TYPE +{ + MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ + MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ + MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ + MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ + MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ + MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ + MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ + MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ + MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ + MAV_TYPE_ROCKET=9, /* Rocket | */ + MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ + MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ + MAV_TYPE_SUBMARINE=12, /* Submarine | */ + MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ + MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ + MAV_TYPE_TRICOPTER=15, /* Octorotor | */ + MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ + MAV_TYPE_ENUM_END=17, /* | */ +}; + +/** @brief */ +enum MAV_COMPONENT +{ + MAV_COMP_ID_ALL=0, /* | */ + MAV_COMP_ID_GPS=220, /* | */ + MAV_COMP_ID_MISSIONPLANNER=190, /* | */ + MAV_COMP_ID_PATHPLANNER=195, /* | */ + MAV_COMP_ID_MAPPER=180, /* | */ + MAV_COMP_ID_CAMERA=100, /* | */ + MAV_COMP_ID_IMU=200, /* | */ + MAV_COMP_ID_IMU_2=201, /* | */ + MAV_COMP_ID_IMU_3=202, /* | */ + MAV_COMP_ID_UDP_BRIDGE=240, /* | */ + MAV_COMP_ID_UART_BRIDGE=241, /* | */ + MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ + MAV_COMP_ID_SERVO1=140, /* | */ + MAV_COMP_ID_SERVO2=141, /* | */ + MAV_COMP_ID_SERVO3=142, /* | */ + MAV_COMP_ID_SERVO4=143, /* | */ + MAV_COMP_ID_SERVO5=144, /* | */ + MAV_COMP_ID_SERVO6=145, /* | */ + MAV_COMP_ID_SERVO7=146, /* | */ + MAV_COMP_ID_SERVO8=147, /* | */ + MAV_COMP_ID_SERVO9=148, /* | */ + MAV_COMP_ID_SERVO10=149, /* | */ + MAV_COMP_ID_SERVO11=150, /* | */ + MAV_COMP_ID_SERVO12=151, /* | */ + MAV_COMP_ID_SERVO13=152, /* | */ + MAV_COMP_ID_SERVO14=153, /* | */ + MAV_COMPONENT_ENUM_END=251, /* | */ +}; + +/** @brief */ +enum MAV_FRAME +{ + MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ + MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ + MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ + MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ + MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ + MAV_FRAME_ENUM_END=5, /* | */ +}; + +/** @brief */ +enum MAVLINK_DATA_STREAM_TYPE +{ + MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ + MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ + MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ + MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ + MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ + MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ +}; + +/** @brief Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ +enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_ENUM_END=253, /* | */ +}; + +/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + */ +enum MAV_DATA_STREAM +{ + MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ + MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ + MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ + MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ + MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ + MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ + MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ + MAV_DATA_STREAM_ENUM_END=13, /* | */ +}; + +/** @brief The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + */ +enum MAV_ROI +{ + MAV_ROI_NONE=0, /* No region of interest. | */ + MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ + MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ + MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ + MAV_ROI_TARGET=4, /* Point toward of given id. | */ + MAV_ROI_ENUM_END=5, /* | */ +}; + +/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ +enum MAV_CMD_ACK +{ + MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ + MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ + MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ + MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ + MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ + MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ + MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ + MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ + MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ + MAV_CMD_ACK_ENUM_END=10, /* | */ +}; + +/** @brief type of a mavlink parameter */ +enum MAV_VAR +{ + MAV_VAR_FLOAT=0, /* 32 bit float | */ + MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */ + MAV_VAR_INT8=2, /* 8 bit signed integer | */ + MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */ + MAV_VAR_INT16=4, /* 16 bit signed integer | */ + MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */ + MAV_VAR_INT32=6, /* 32 bit signed integer | */ + MAV_VAR_ENUM_END=7, /* | */ +}; + +/** @brief result from a mavlink command */ +enum MAV_RESULT +{ + MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ + MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ + MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ + MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ + MAV_RESULT_FAILED=4, /* Command executed, but failed | */ + MAV_RESULT_ENUM_END=5, /* | */ +}; + +/** @brief result in a mavlink mission ack */ +enum MAV_MISSION_RESULT +{ + MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ + MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ + MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ + MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ + MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ + MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ + MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ + MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ + MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ + MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ + MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ + MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ + MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ + MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ + MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ + MAV_MISSION_RESULT_ENUM_END=15, /* | */ +}; + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" +#include "./mavlink_msg_sys_status.h" +#include "./mavlink_msg_system_time.h" +#include "./mavlink_msg_ping.h" +#include "./mavlink_msg_change_operator_control.h" +#include "./mavlink_msg_change_operator_control_ack.h" +#include "./mavlink_msg_auth_key.h" +#include "./mavlink_msg_set_mode.h" +#include "./mavlink_msg_param_request_read.h" +#include "./mavlink_msg_param_request_list.h" +#include "./mavlink_msg_param_value.h" +#include "./mavlink_msg_param_set.h" +#include "./mavlink_msg_gps_raw_int.h" +#include "./mavlink_msg_gps_status.h" +#include "./mavlink_msg_scaled_imu.h" +#include "./mavlink_msg_raw_imu.h" +#include "./mavlink_msg_raw_pressure.h" +#include "./mavlink_msg_scaled_pressure.h" +#include "./mavlink_msg_attitude.h" +#include "./mavlink_msg_attitude_quaternion.h" +#include "./mavlink_msg_local_position_ned.h" +#include "./mavlink_msg_global_position_int.h" +#include "./mavlink_msg_rc_channels_raw.h" +#include "./mavlink_msg_rc_channels_scaled.h" +#include "./mavlink_msg_servo_output_raw.h" +#include "./mavlink_msg_mission_item.h" +#include "./mavlink_msg_mission_request.h" +#include "./mavlink_msg_mission_set_current.h" +#include "./mavlink_msg_mission_current.h" +#include "./mavlink_msg_mission_request_list.h" +#include "./mavlink_msg_mission_count.h" +#include "./mavlink_msg_mission_clear_all.h" +#include "./mavlink_msg_mission_item_reached.h" +#include "./mavlink_msg_mission_ack.h" +#include "./mavlink_msg_set_gps_global_origin.h" +#include "./mavlink_msg_gps_global_origin.h" +#include "./mavlink_msg_set_local_position_setpoint.h" +#include "./mavlink_msg_local_position_setpoint.h" +#include "./mavlink_msg_global_position_setpoint_int.h" +#include "./mavlink_msg_set_global_position_setpoint_int.h" +#include "./mavlink_msg_safety_set_allowed_area.h" +#include "./mavlink_msg_safety_allowed_area.h" +#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h" +#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h" +#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h" +#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h" +#include "./mavlink_msg_nav_controller_output.h" +#include "./mavlink_msg_state_correction.h" +#include "./mavlink_msg_request_data_stream.h" +#include "./mavlink_msg_data_stream.h" +#include "./mavlink_msg_manual_control.h" +#include "./mavlink_msg_rc_channels_override.h" +#include "./mavlink_msg_vfr_hud.h" +#include "./mavlink_msg_command_short.h" +#include "./mavlink_msg_command_long.h" +#include "./mavlink_msg_command_ack.h" +#include "./mavlink_msg_hil_state.h" +#include "./mavlink_msg_hil_controls.h" +#include "./mavlink_msg_hil_rc_inputs_raw.h" +#include "./mavlink_msg_optical_flow.h" +#include "./mavlink_msg_global_vision_position_estimate.h" +#include "./mavlink_msg_vision_position_estimate.h" +#include "./mavlink_msg_vision_speed_estimate.h" +#include "./mavlink_msg_vicon_position_estimate.h" +#include "./mavlink_msg_memory_vect.h" +#include "./mavlink_msg_debug_vect.h" +#include "./mavlink_msg_named_value_float.h" +#include "./mavlink_msg_named_value_int.h" +#include "./mavlink_msg_statustext.h" +#include "./mavlink_msg_debug.h" +#include "./mavlink_msg_extended_message.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // COMMON_H diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink.h new file mode 100644 index 0000000000..17b7329709 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from common.xml + * @see http://pixhawk.ethz.ch/software/mavlink + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX 254 +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS 1 +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA 1 +#endif + +#include "version.h" +#include "common.h" + +#endif // MAVLINK_H diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h new file mode 100644 index 0000000000..16045b9747 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude.h @@ -0,0 +1,276 @@ +// MESSAGE ATTITUDE PACKING + +#define MAVLINK_MSG_ID_ATTITUDE 30 + +typedef struct __mavlink_attitude_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) +} mavlink_attitude_t; + +#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 +#define MAVLINK_MSG_ID_30_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ + "ATTITUDE", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + return mavlink_finalize_message(msg, system_id, component_id, 28, 39); +} + +/** + * @brief Pack a attitude message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39); +} + +/** + * @brief Encode a attitude struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) +{ + return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); +} + +/** + * @brief Send a attitude message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, rollspeed); + _mav_put_float(buf, 20, pitchspeed); + _mav_put_float(buf, 24, yawspeed); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 28, 39); +#else + mavlink_attitude_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 28, 39); +#endif +} + +#endif + +// MESSAGE ATTITUDE UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from attitude message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from attitude message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from attitude message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field rollspeed from attitude message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field pitchspeed from attitude message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field yawspeed from attitude message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a attitude message into a struct + * + * @param msg The message to decode + * @param attitude C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); + attitude->roll = mavlink_msg_attitude_get_roll(msg); + attitude->pitch = mavlink_msg_attitude_get_pitch(msg); + attitude->yaw = mavlink_msg_attitude_get_yaw(msg); + attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); + attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); + attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); +#else + memcpy(attitude, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h new file mode 100644 index 0000000000..215aff6d03 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_attitude_quaternion.h @@ -0,0 +1,298 @@ +// MESSAGE ATTITUDE_QUATERNION PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 + +typedef struct __mavlink_attitude_quaternion_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float q1; ///< Quaternion component 1 + float q2; ///< Quaternion component 2 + float q3; ///< Quaternion component 3 + float q4; ///< Quaternion component 4 + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) +} mavlink_attitude_quaternion_t; + +#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 +#define MAVLINK_MSG_ID_31_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ + "ATTITUDE_QUATERNION", \ + 8, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ + { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ + { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ + { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ + { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ + } \ +} + + +/** + * @brief Pack a attitude_quaternion message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + return mavlink_finalize_message(msg, system_id, component_id, 32, 246); +} + +/** + * @brief Pack a attitude_quaternion message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 246); +} + +/** + * @brief Encode a attitude_quaternion struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_quaternion C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) +{ + return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); +} + +/** + * @brief Send a attitude_quaternion message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param q1 Quaternion component 1 + * @param q2 Quaternion component 2 + * @param q3 Quaternion component 3 + * @param q4 Quaternion component 4 + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, q1); + _mav_put_float(buf, 8, q2); + _mav_put_float(buf, 12, q3); + _mav_put_float(buf, 16, q4); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, 32, 246); +#else + mavlink_attitude_quaternion_t packet; + packet.time_boot_ms = time_boot_ms; + packet.q1 = q1; + packet.q2 = q2; + packet.q3 = q3; + packet.q4 = q4; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, 32, 246); +#endif +} + +#endif + +// MESSAGE ATTITUDE_QUATERNION UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_quaternion message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field q1 from attitude_quaternion message + * + * @return Quaternion component 1 + */ +static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field q2 from attitude_quaternion message + * + * @return Quaternion component 2 + */ +static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field q3 from attitude_quaternion message + * + * @return Quaternion component 3 + */ +static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field q4 from attitude_quaternion message + * + * @return Quaternion component 4 + */ +static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from attitude_quaternion message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from attitude_quaternion message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from attitude_quaternion message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a attitude_quaternion message into a struct + * + * @param msg The message to decode + * @param attitude_quaternion C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); + attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); + attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); + attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); + attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); + attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); + attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); + attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); +#else + memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h new file mode 100644 index 0000000000..366805f111 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_auth_key.h @@ -0,0 +1,144 @@ +// MESSAGE AUTH_KEY PACKING + +#define MAVLINK_MSG_ID_AUTH_KEY 7 + +typedef struct __mavlink_auth_key_t +{ + char key[32]; ///< key +} mavlink_auth_key_t; + +#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 +#define MAVLINK_MSG_ID_7_LEN 32 + +#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 + +#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ + "AUTH_KEY", \ + 1, \ + { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ + } \ +} + + +/** + * @brief Pack a auth_key message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_auth_key_t packet; + + memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + return mavlink_finalize_message(msg, system_id, component_id, 32, 119); +} + +/** + * @brief Pack a auth_key message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param key key + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_auth_key_t packet; + + memcpy(packet.key, key, sizeof(char)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119); +} + +/** + * @brief Encode a auth_key struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param auth_key C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) +{ + return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); +} + +/** + * @brief Send a auth_key message + * @param chan MAVLink channel to send the message + * + * @param key key + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + + _mav_put_char_array(buf, 0, key, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32, 119); +#else + mavlink_auth_key_t packet; + + memcpy(packet.key, key, sizeof(char)*32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32, 119); +#endif +} + +#endif + +// MESSAGE AUTH_KEY UNPACKING + + +/** + * @brief Get field key from auth_key message + * + * @return key + */ +static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) +{ + return _MAV_RETURN_char_array(msg, key, 32, 0); +} + +/** + * @brief Decode a auth_key message into a struct + * + * @param msg The message to decode + * @param auth_key C-struct to decode the message contents into + */ +static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_auth_key_get_key(msg, auth_key->key); +#else + memcpy(auth_key, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h new file mode 100644 index 0000000000..1b164d0b86 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control.h @@ -0,0 +1,204 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 + +typedef struct __mavlink_change_operator_control_t +{ + uint8_t target_system; ///< System the GCS requests control for + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" +} mavlink_change_operator_control_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 +#define MAVLINK_MSG_ID_5_LEN 28 + +#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ + "CHANGE_OPERATOR_CONTROL", \ + 4, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ + { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ + { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 28, 217); +} + +/** + * @brief Pack a change_operator_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + memcpy(packet.passkey, passkey, sizeof(char)*25); + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217); +} + +/** + * @brief Encode a change_operator_control struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) +{ + return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); +} + +/** + * @brief Send a change_operator_control message + * @param chan MAVLink channel to send the message + * + * @param target_system System the GCS requests control for + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, version); + _mav_put_char_array(buf, 3, passkey, 25); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28, 217); +#else + mavlink_change_operator_control_t packet; + packet.target_system = target_system; + packet.control_request = control_request; + packet.version = version; + memcpy(packet.passkey, passkey, sizeof(char)*25); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28, 217); +#endif +} + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING + + +/** + * @brief Get field target_system from change_operator_control message + * + * @return System the GCS requests control for + */ +static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field version from change_operator_control message + * + * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + */ +static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field passkey from change_operator_control message + * + * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + */ +static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) +{ + return _MAV_RETURN_char_array(msg, passkey, 25, 3); +} + +/** + * @brief Decode a change_operator_control message into a struct + * + * @param msg The message to decode + * @param change_operator_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); + change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); + change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); + mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); +#else + memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h new file mode 100644 index 0000000000..25e6a6d831 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_change_operator_control_ack.h @@ -0,0 +1,188 @@ +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 + +typedef struct __mavlink_change_operator_control_ack_t +{ + uint8_t gcs_system_id; ///< ID of the GCS this message + uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV + uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control +} mavlink_change_operator_control_ack_t; + +#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 +#define MAVLINK_MSG_ID_6_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ + "CHANGE_OPERATOR_CONTROL_ACK", \ + 3, \ + { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ + { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ + { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ + } \ +} + + +/** + * @brief Pack a change_operator_control_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 104); +} + +/** + * @brief Pack a change_operator_control_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104); +} + +/** + * @brief Encode a change_operator_control_ack struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param change_operator_control_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ + return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); +} + +/** + * @brief Send a change_operator_control_ack message + * @param chan MAVLink channel to send the message + * + * @param gcs_system_id ID of the GCS this message + * @param control_request 0: request control of this MAV, 1: Release control of this MAV + * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, gcs_system_id); + _mav_put_uint8_t(buf, 1, control_request); + _mav_put_uint8_t(buf, 2, ack); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3, 104); +#else + mavlink_change_operator_control_ack_t packet; + packet.gcs_system_id = gcs_system_id; + packet.control_request = control_request; + packet.ack = ack; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3, 104); +#endif +} + +#endif + +// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING + + +/** + * @brief Get field gcs_system_id from change_operator_control_ack message + * + * @return ID of the GCS this message + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field control_request from change_operator_control_ack message + * + * @return 0: request control of this MAV, 1: Release control of this MAV + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field ack from change_operator_control_ack message + * + * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + */ +static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a change_operator_control_ack message into a struct + * + * @param msg The message to decode + * @param change_operator_control_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); + change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); + change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); +#else + memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h new file mode 100644 index 0000000000..2109e32072 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_ack.h @@ -0,0 +1,166 @@ +// MESSAGE COMMAND_ACK PACKING + +#define MAVLINK_MSG_ID_COMMAND_ACK 77 + +typedef struct __mavlink_command_ack_t +{ + uint16_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t result; ///< See MAV_RESULT enum +} mavlink_command_ack_t; + +#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 +#define MAVLINK_MSG_ID_77_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ + "COMMAND_ACK", \ + 2, \ + { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ + { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ + } \ +} + + +/** + * @brief Pack a command_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 143); +} + +/** + * @brief Pack a command_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t command,uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143); +} + +/** + * @brief Encode a command_ack struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) +{ + return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); +} + +/** + * @brief Send a command_ack message + * @param chan MAVLink channel to send the message + * + * @param command Command ID, as defined by MAV_CMD enum. + * @param result See MAV_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, command); + _mav_put_uint8_t(buf, 2, result); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143); +#else + mavlink_command_ack_t packet; + packet.command = command; + packet.result = result; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143); +#endif +} + +#endif + +// MESSAGE COMMAND_ACK UNPACKING + + +/** + * @brief Get field command from command_ack message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field result from command_ack message + * + * @return See MAV_RESULT enum + */ +static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a command_ack message into a struct + * + * @param msg The message to decode + * @param command_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_ack->command = mavlink_msg_command_ack_get_command(msg); + command_ack->result = mavlink_msg_command_ack_get_result(msg); +#else + memcpy(command_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h new file mode 100644 index 0000000000..44fd8c10bf --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_long.h @@ -0,0 +1,364 @@ +// MESSAGE COMMAND_LONG PACKING + +#define MAVLINK_MSG_ID_COMMAND_LONG 76 + +typedef struct __mavlink_command_long_t +{ + float param1; ///< Parameter 1, as defined by MAV_CMD enum. + float param2; ///< Parameter 2, as defined by MAV_CMD enum. + float param3; ///< Parameter 3, as defined by MAV_CMD enum. + float param4; ///< Parameter 4, as defined by MAV_CMD enum. + float param5; ///< Parameter 5, as defined by MAV_CMD enum. + float param6; ///< Parameter 6, as defined by MAV_CMD enum. + float param7; ///< Parameter 7, as defined by MAV_CMD enum. + uint8_t target_system; ///< System which should execute the command + uint8_t target_component; ///< Component which should execute the command, 0 for all components + uint8_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +} mavlink_command_long_t; + +#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 32 +#define MAVLINK_MSG_ID_76_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ + "COMMAND_LONG", \ + 11, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ + { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ + { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ + { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_command_long_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_command_long_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, command) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, confirmation) }, \ + } \ +} + + +/** + * @brief Pack a command_long message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint8_t(buf, 28, target_system); + _mav_put_uint8_t(buf, 29, target_component); + _mav_put_uint8_t(buf, 30, command); + _mav_put_uint8_t(buf, 31, confirmation); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; + return mavlink_finalize_message(msg, system_id, component_id, 32, 168); +} + +/** + * @brief Pack a command_long message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint8_t(buf, 28, target_system); + _mav_put_uint8_t(buf, 29, target_component); + _mav_put_uint8_t(buf, 30, command); + _mav_put_uint8_t(buf, 31, confirmation); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 168); +} + +/** + * @brief Encode a command_long struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_long C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) +{ + return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); +} + +/** + * @brief Send a command_long message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @param param5 Parameter 5, as defined by MAV_CMD enum. + * @param param6 Parameter 6, as defined by MAV_CMD enum. + * @param param7 Parameter 7, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, param5); + _mav_put_float(buf, 20, param6); + _mav_put_float(buf, 24, param7); + _mav_put_uint8_t(buf, 28, target_system); + _mav_put_uint8_t(buf, 29, target_component); + _mav_put_uint8_t(buf, 30, command); + _mav_put_uint8_t(buf, 31, confirmation); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, 32, 168); +#else + mavlink_command_long_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.param5 = param5; + packet.param6 = param6; + packet.param7 = param7; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, 32, 168); +#endif +} + +#endif + +// MESSAGE COMMAND_LONG UNPACKING + + +/** + * @brief Get field target_system from command_long message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field target_component from command_long message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Get field command from command_long message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint8_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field confirmation from command_long message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field param1 from command_long message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_long message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_long message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_long message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field param5 from command_long message + * + * @return Parameter 5, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field param6 from command_long message + * + * @return Parameter 6, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field param7 from command_long message + * + * @return Parameter 7, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a command_long message into a struct + * + * @param msg The message to decode + * @param command_long C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_long->param1 = mavlink_msg_command_long_get_param1(msg); + command_long->param2 = mavlink_msg_command_long_get_param2(msg); + command_long->param3 = mavlink_msg_command_long_get_param3(msg); + command_long->param4 = mavlink_msg_command_long_get_param4(msg); + command_long->param5 = mavlink_msg_command_long_get_param5(msg); + command_long->param6 = mavlink_msg_command_long_get_param6(msg); + command_long->param7 = mavlink_msg_command_long_get_param7(msg); + command_long->target_system = mavlink_msg_command_long_get_target_system(msg); + command_long->target_component = mavlink_msg_command_long_get_target_component(msg); + command_long->command = mavlink_msg_command_long_get_command(msg); + command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); +#else + memcpy(command_long, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_short.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_short.h new file mode 100644 index 0000000000..f4a087b3e1 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_command_short.h @@ -0,0 +1,298 @@ +// MESSAGE COMMAND_SHORT PACKING + +#define MAVLINK_MSG_ID_COMMAND_SHORT 75 + +typedef struct __mavlink_command_short_t +{ + float param1; ///< Parameter 1, as defined by MAV_CMD enum. + float param2; ///< Parameter 2, as defined by MAV_CMD enum. + float param3; ///< Parameter 3, as defined by MAV_CMD enum. + float param4; ///< Parameter 4, as defined by MAV_CMD enum. + uint8_t target_system; ///< System which should execute the command + uint8_t target_component; ///< Component which should execute the command, 0 for all components + uint8_t command; ///< Command ID, as defined by MAV_CMD enum. + uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) +} mavlink_command_short_t; + +#define MAVLINK_MSG_ID_COMMAND_SHORT_LEN 20 +#define MAVLINK_MSG_ID_75_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_COMMAND_SHORT { \ + "COMMAND_SHORT", \ + 8, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_short_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_short_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_short_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_short_t, param4) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_command_short_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_command_short_t, target_component) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_command_short_t, command) }, \ + { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_command_short_t, confirmation) }, \ + } \ +} + + +/** + * @brief Pack a command_short message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_short_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, command); + _mav_put_uint8_t(buf, 19, confirmation); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_command_short_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 160); +} + +/** + * @brief Pack a command_short message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_command_short_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t command,uint8_t confirmation,float param1,float param2,float param3,float param4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, command); + _mav_put_uint8_t(buf, 19, confirmation); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_command_short_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_COMMAND_SHORT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 160); +} + +/** + * @brief Encode a command_short struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param command_short C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_command_short_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_short_t* command_short) +{ + return mavlink_msg_command_short_pack(system_id, component_id, msg, command_short->target_system, command_short->target_component, command_short->command, command_short->confirmation, command_short->param1, command_short->param2, command_short->param3, command_short->param4); +} + +/** + * @brief Send a command_short message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param command Command ID, as defined by MAV_CMD enum. + * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + * @param param1 Parameter 1, as defined by MAV_CMD enum. + * @param param2 Parameter 2, as defined by MAV_CMD enum. + * @param param3 Parameter 3, as defined by MAV_CMD enum. + * @param param4 Parameter 4, as defined by MAV_CMD enum. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_command_short_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, command); + _mav_put_uint8_t(buf, 19, confirmation); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_SHORT, buf, 20, 160); +#else + mavlink_command_short_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.target_system = target_system; + packet.target_component = target_component; + packet.command = command; + packet.confirmation = confirmation; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_SHORT, (const char *)&packet, 20, 160); +#endif +} + +#endif + +// MESSAGE COMMAND_SHORT UNPACKING + + +/** + * @brief Get field target_system from command_short message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_command_short_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from command_short message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_command_short_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field command from command_short message + * + * @return Command ID, as defined by MAV_CMD enum. + */ +static inline uint8_t mavlink_msg_command_short_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field confirmation from command_short message + * + * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + */ +static inline uint8_t mavlink_msg_command_short_get_confirmation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field param1 from command_short message + * + * @return Parameter 1, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_short_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from command_short message + * + * @return Parameter 2, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_short_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from command_short message + * + * @return Parameter 3, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_short_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from command_short message + * + * @return Parameter 4, as defined by MAV_CMD enum. + */ +static inline float mavlink_msg_command_short_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a command_short message into a struct + * + * @param msg The message to decode + * @param command_short C-struct to decode the message contents into + */ +static inline void mavlink_msg_command_short_decode(const mavlink_message_t* msg, mavlink_command_short_t* command_short) +{ +#if MAVLINK_NEED_BYTE_SWAP + command_short->param1 = mavlink_msg_command_short_get_param1(msg); + command_short->param2 = mavlink_msg_command_short_get_param2(msg); + command_short->param3 = mavlink_msg_command_short_get_param3(msg); + command_short->param4 = mavlink_msg_command_short_get_param4(msg); + command_short->target_system = mavlink_msg_command_short_get_target_system(msg); + command_short->target_component = mavlink_msg_command_short_get_target_component(msg); + command_short->command = mavlink_msg_command_short_get_command(msg); + command_short->confirmation = mavlink_msg_command_short_get_confirmation(msg); +#else + memcpy(command_short, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h new file mode 100644 index 0000000000..1c8df4b413 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_data_stream.h @@ -0,0 +1,188 @@ +// MESSAGE DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_DATA_STREAM 67 + +typedef struct __mavlink_data_stream_t +{ + uint16_t message_rate; ///< The requested interval between two messages of this type + uint8_t stream_id; ///< The ID of the requested data stream + uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped. +} mavlink_data_stream_t; + +#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 +#define MAVLINK_MSG_ID_67_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ + "DATA_STREAM", \ + 3, \ + { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ + { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ + { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ + } \ +} + + +/** + * @brief Pack a data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; + return mavlink_finalize_message(msg, system_id, component_id, 4, 21); +} + +/** + * @brief Pack a data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t stream_id,uint16_t message_rate,uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21); +} + +/** + * @brief Encode a data_stream struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) +{ + return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); +} + +/** + * @brief Send a data_stream message + * @param chan MAVLink channel to send the message + * + * @param stream_id The ID of the requested data stream + * @param message_rate The requested interval between two messages of this type + * @param on_off 1 stream is enabled, 0 stream is stopped. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, message_rate); + _mav_put_uint8_t(buf, 2, stream_id); + _mav_put_uint8_t(buf, 3, on_off); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, 4, 21); +#else + mavlink_data_stream_t packet; + packet.message_rate = message_rate; + packet.stream_id = stream_id; + packet.on_off = on_off; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, 4, 21); +#endif +} + +#endif + +// MESSAGE DATA_STREAM UNPACKING + + +/** + * @brief Get field stream_id from data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field message_rate from data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field on_off from data_stream message + * + * @return 1 stream is enabled, 0 stream is stopped. + */ +static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Decode a data_stream message into a struct + * + * @param msg The message to decode + * @param data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); + data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); + data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); +#else + memcpy(data_stream, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h new file mode 100644 index 0000000000..1687a16cd2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug.h @@ -0,0 +1,188 @@ +// MESSAGE DEBUG PACKING + +#define MAVLINK_MSG_ID_DEBUG 254 + +typedef struct __mavlink_debug_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float value; ///< DEBUG value + uint8_t ind; ///< index of debug variable +} mavlink_debug_t; + +#define MAVLINK_MSG_ID_DEBUG_LEN 9 +#define MAVLINK_MSG_ID_254_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_DEBUG { \ + "DEBUG", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ + { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ + } \ +} + + +/** + * @brief Pack a debug message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; + return mavlink_finalize_message(msg, system_id, component_id, 9, 46); +} + +/** + * @brief Pack a debug message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t ind,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46); +} + +/** + * @brief Encode a debug struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) +{ + return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); +} + +/** + * @brief Send a debug message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param ind index of debug variable + * @param value DEBUG value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_uint8_t(buf, 8, ind); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 9, 46); +#else + mavlink_debug_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + packet.ind = ind; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 9, 46); +#endif +} + +#endif + +// MESSAGE DEBUG UNPACKING + + +/** + * @brief Get field time_boot_ms from debug message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field ind from debug message + * + * @return index of debug variable + */ +static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field value from debug message + * + * @return DEBUG value + */ +static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a debug message into a struct + * + * @param msg The message to decode + * @param debug C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); + debug->value = mavlink_msg_debug_get_value(msg); + debug->ind = mavlink_msg_debug_get_ind(msg); +#else + memcpy(debug, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h new file mode 100644 index 0000000000..7d0b6e6e67 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_debug_vect.h @@ -0,0 +1,226 @@ +// MESSAGE DEBUG_VECT PACKING + +#define MAVLINK_MSG_ID_DEBUG_VECT 250 + +typedef struct __mavlink_debug_vect_t +{ + uint64_t time_usec; ///< Timestamp + float x; ///< x + float y; ///< y + float z; ///< z + char name[10]; ///< Name +} mavlink_debug_vect_t; + +#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 +#define MAVLINK_MSG_ID_250_LEN 30 + +#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ + "DEBUG_VECT", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ + } \ +} + + +/** + * @brief Pack a debug_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + return mavlink_finalize_message(msg, system_id, component_id, 30, 49); +} + +/** + * @brief Pack a debug_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *name,uint64_t time_usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49); +} + +/** + * @brief Encode a debug_vect struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param debug_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) +{ + return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); +} + +/** + * @brief Send a debug_vect message + * @param chan MAVLink channel to send the message + * + * @param name Name + * @param time_usec Timestamp + * @param x x + * @param y y + * @param z z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_char_array(buf, 20, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49); +#else + mavlink_debug_vect_t packet; + packet.time_usec = time_usec; + packet.x = x; + packet.y = y; + packet.z = z; + memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49); +#endif +} + +#endif + +// MESSAGE DEBUG_VECT UNPACKING + + +/** + * @brief Get field name from debug_vect message + * + * @return Name + */ +static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 20); +} + +/** + * @brief Get field time_usec from debug_vect message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from debug_vect message + * + * @return x + */ +static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from debug_vect message + * + * @return y + */ +static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from debug_vect message + * + * @return z + */ +static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a debug_vect message into a struct + * + * @param msg The message to decode + * @param debug_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); + debug_vect->x = mavlink_msg_debug_vect_get_x(msg); + debug_vect->y = mavlink_msg_debug_vect_get_y(msg); + debug_vect->z = mavlink_msg_debug_vect_get_z(msg); + mavlink_msg_debug_vect_get_name(msg, debug_vect->name); +#else + memcpy(debug_vect, _MAV_PAYLOAD(msg), 30); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h new file mode 100644 index 0000000000..2c42739be7 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_extended_message.h @@ -0,0 +1,188 @@ +// MESSAGE EXTENDED_MESSAGE PACKING + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 + +typedef struct __mavlink_extended_message_t +{ + uint8_t target_system; ///< System which should execute the command + uint8_t target_component; ///< Component which should execute the command, 0 for all components + uint8_t protocol_flags; ///< Retransmission / ACK flags +} mavlink_extended_message_t; + +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE_LEN 3 +#define MAVLINK_MSG_ID_255_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE { \ + "EXTENDED_MESSAGE", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_message_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_message_t, target_component) }, \ + { "protocol_flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_extended_message_t, protocol_flags) }, \ + } \ +} + + +/** + * @brief Pack a extended_message message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param protocol_flags Retransmission / ACK flags + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_message_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t protocol_flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, protocol_flags); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_extended_message_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.protocol_flags = protocol_flags; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; + return mavlink_finalize_message(msg, system_id, component_id, 3, 247); +} + +/** + * @brief Pack a extended_message message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param protocol_flags Retransmission / ACK flags + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_extended_message_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t protocol_flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, protocol_flags); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_extended_message_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.protocol_flags = protocol_flags; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 247); +} + +/** + * @brief Encode a extended_message struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param extended_message C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_extended_message_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_message_t* extended_message) +{ + return mavlink_msg_extended_message_pack(system_id, component_id, msg, extended_message->target_system, extended_message->target_component, extended_message->protocol_flags); +} + +/** + * @brief Send a extended_message message + * @param chan MAVLink channel to send the message + * + * @param target_system System which should execute the command + * @param target_component Component which should execute the command, 0 for all components + * @param protocol_flags Retransmission / ACK flags + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t protocol_flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, protocol_flags); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, buf, 3, 247); +#else + mavlink_extended_message_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.protocol_flags = protocol_flags; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, (const char *)&packet, 3, 247); +#endif +} + +#endif + +// MESSAGE EXTENDED_MESSAGE UNPACKING + + +/** + * @brief Get field target_system from extended_message message + * + * @return System which should execute the command + */ +static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from extended_message message + * + * @return Component which should execute the command, 0 for all components + */ +static inline uint8_t mavlink_msg_extended_message_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field protocol_flags from extended_message message + * + * @return Retransmission / ACK flags + */ +static inline uint8_t mavlink_msg_extended_message_get_protocol_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a extended_message message into a struct + * + * @param msg The message to decode + * @param extended_message C-struct to decode the message contents into + */ +static inline void mavlink_msg_extended_message_decode(const mavlink_message_t* msg, mavlink_extended_message_t* extended_message) +{ +#if MAVLINK_NEED_BYTE_SWAP + extended_message->target_system = mavlink_msg_extended_message_get_target_system(msg); + extended_message->target_component = mavlink_msg_extended_message_get_target_component(msg); + extended_message->protocol_flags = mavlink_msg_extended_message_get_protocol_flags(msg); +#else + memcpy(extended_message, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position.h new file mode 100644 index 0000000000..6e902393da --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position.h @@ -0,0 +1,276 @@ +// MESSAGE GLOBAL_POSITION PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION 33 + +typedef struct __mavlink_global_position_t +{ + uint64_t usec; ///< Timestamp (microseconds since unix epoch) + float lat; ///< Latitude, in degrees + float lon; ///< Longitude, in degrees + float alt; ///< Absolute altitude, in meters + float vx; ///< X Speed (in Latitude direction, positive: going north) + float vy; ///< Y Speed (in Longitude direction, positive: going east) + float vz; ///< Z Speed (in Altitude direction, positive: going up) +} mavlink_global_position_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32 +#define MAVLINK_MSG_ID_33_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \ + "GLOBAL_POSITION", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \ + } \ +} + + +/** + * @brief Pack a global_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, vx); + _mav_put_float(buf, 24, vy); + _mav_put_float(buf, 28, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_global_position_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; + return mavlink_finalize_message(msg, system_id, component_id, 32, 147); +} + +/** + * @brief Pack a global_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, vx); + _mav_put_float(buf, 24, vy); + _mav_put_float(buf, 28, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_global_position_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 147); +} + +/** + * @brief Encode a global_position struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position) +{ + return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz); +} + +/** + * @brief Send a global_position message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since unix epoch) + * @param lat Latitude, in degrees + * @param lon Longitude, in degrees + * @param alt Absolute altitude, in meters + * @param vx X Speed (in Latitude direction, positive: going north) + * @param vy Y Speed (in Longitude direction, positive: going east) + * @param vz Z Speed (in Altitude direction, positive: going up) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, vx); + _mav_put_float(buf, 24, vy); + _mav_put_float(buf, 28, vz); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, buf, 32, 147); +#else + mavlink_global_position_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, (const char *)&packet, 32, 147); +#endif +} + +#endif + +// MESSAGE GLOBAL_POSITION UNPACKING + + +/** + * @brief Get field usec from global_position message + * + * @return Timestamp (microseconds since unix epoch) + */ +static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field lat from global_position message + * + * @return Latitude, in degrees + */ +static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field lon from global_position message + * + * @return Longitude, in degrees + */ +static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field alt from global_position message + * + * @return Absolute altitude, in meters + */ +static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vx from global_position message + * + * @return X Speed (in Latitude direction, positive: going north) + */ +static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vy from global_position message + * + * @return Y Speed (in Longitude direction, positive: going east) + */ +static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vz from global_position message + * + * @return Z Speed (in Altitude direction, positive: going up) + */ +static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a global_position message into a struct + * + * @param msg The message to decode + * @param global_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position->usec = mavlink_msg_global_position_get_usec(msg); + global_position->lat = mavlink_msg_global_position_get_lat(msg); + global_position->lon = mavlink_msg_global_position_get_lon(msg); + global_position->alt = mavlink_msg_global_position_get_alt(msg); + global_position->vx = mavlink_msg_global_position_get_vx(msg); + global_position->vy = mavlink_msg_global_position_get_vy(msg); + global_position->vz = mavlink_msg_global_position_get_vz(msg); +#else + memcpy(global_position, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h new file mode 100644 index 0000000000..3d624bc051 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_int.h @@ -0,0 +1,320 @@ +// MESSAGE GLOBAL_POSITION_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 34 + +typedef struct __mavlink_global_position_int_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int32_t lat; ///< Latitude, expressed as * 1E7 + int32_t lon; ///< Longitude, expressed as * 1E7 + int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL + int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters) + int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 + int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 + int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 +} mavlink_global_position_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 +#define MAVLINK_MSG_ID_34_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ + "GLOBAL_POSITION_INT", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ + { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ + { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ + } \ +} + + +/** + * @brief Pack a global_position_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + return mavlink_finalize_message(msg, system_id, component_id, 28, 104); +} + +/** + * @brief Pack a global_position_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 104); +} + +/** + * @brief Encode a global_position_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) +{ + return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); +} + +/** + * @brief Send a global_position_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL + * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat); + _mav_put_int32_t(buf, 8, lon); + _mav_put_int32_t(buf, 12, alt); + _mav_put_int32_t(buf, 16, relative_alt); + _mav_put_int16_t(buf, 20, vx); + _mav_put_int16_t(buf, 22, vy); + _mav_put_int16_t(buf, 24, vz); + _mav_put_uint16_t(buf, 26, hdg); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 28, 104); +#else + mavlink_global_position_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.relative_alt = relative_alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.hdg = hdg; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 28, 104); +#endif +} + +#endif + +// MESSAGE GLOBAL_POSITION_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field lat from global_position_int message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon from global_position_int message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from global_position_int message + * + * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL + */ +static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field relative_alt from global_position_int message + * + * @return Altitude above ground in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field vx from global_position_int message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field vy from global_position_int message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field vz from global_position_int message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Get field hdg from global_position_int message + * + * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Decode a global_position_int message into a struct + * + * @param msg The message to decode + * @param global_position_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); + global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); + global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); + global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); + global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); + global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); + global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); + global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); + global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); +#else + memcpy(global_position_int, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h new file mode 100644 index 0000000000..e38df91dcf --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_position_setpoint_int.h @@ -0,0 +1,232 @@ +// MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52 + +typedef struct __mavlink_global_position_setpoint_int_t +{ + int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 + int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 + int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int16_t yaw; ///< Desired yaw angle in degrees * 100 + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT +} mavlink_global_position_setpoint_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 +#define MAVLINK_MSG_ID_52_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \ + "GLOBAL_POSITION_SETPOINT_INT", \ + 5, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \ + { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a global_position_setpoint_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 15); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message(msg, system_id, component_id, 15, 141); +} + +/** + * @brief Pack a global_position_setpoint_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 15); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 141); +} + +/** + * @brief Encode a global_position_setpoint_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_setpoint_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int) +{ + return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw); +} + +/** + * @brief Send a global_position_setpoint_int message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141); +#else + mavlink_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141); +#endif +} + +#endif + +// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING + + +/** + * @brief Get field coordinate_frame from global_position_setpoint_int message + * + * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + */ +static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field latitude from global_position_setpoint_int message + * + * @return WGS84 Latitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from global_position_setpoint_int message + * + * @return WGS84 Longitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from global_position_setpoint_int message + * + * @return WGS84 Altitude in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field yaw from global_position_setpoint_int message + * + * @return Desired yaw angle in degrees * 100 + */ +static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a global_position_setpoint_int message into a struct + * + * @param msg The message to decode + * @param global_position_setpoint_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_global_position_setpoint_int_t* global_position_setpoint_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_setpoint_int->latitude = mavlink_msg_global_position_setpoint_int_get_latitude(msg); + global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg); + global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg); + global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg); + global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg); +#else + memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h new file mode 100644 index 0000000000..06c6357b1f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_global_vision_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 + +typedef struct __mavlink_global_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_global_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_101_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ + "GLOBAL_VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a global_vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 102); +} + +/** + * @brief Pack a global_vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 102); +} + +/** + * @brief Encode a global_vision_position_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ + return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); +} + +/** + * @brief Send a global_vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, 32, 102); +#else + mavlink_global_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 102); +#endif +} + +#endif + +// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from global_vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from global_vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from global_vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from global_vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from global_vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from global_vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from global_vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a global_vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param global_vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); + global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); + global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); + global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); + global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); + global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); + global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); +#else + memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h new file mode 100644 index 0000000000..3df5a58f95 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_global_origin.h @@ -0,0 +1,188 @@ +// MESSAGE GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 + +typedef struct __mavlink_gps_global_origin_t +{ + int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7 + int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7 + int32_t altitude; ///< Altitude(WGS84), expressed as * 1000 +} mavlink_gps_global_origin_t; + +#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 +#define MAVLINK_MSG_ID_49_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ + "GPS_GLOBAL_ORIGIN", \ + 3, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ + } \ +} + + +/** + * @brief Pack a gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message(msg, system_id, component_id, 12, 39); +} + +/** + * @brief Pack a gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39); +} + +/** + * @brief Encode a gps_global_origin struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) +{ + return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); +} + +/** + * @brief Send a gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param latitude Latitude (WGS84), expressed as * 1E7 + * @param longitude Longitude (WGS84), expressed as * 1E7 + * @param altitude Altitude(WGS84), expressed as * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, 12, 39); +#else + mavlink_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, 12, 39); +#endif +} + +#endif + +// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field latitude from gps_global_origin message + * + * @return Latitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from gps_global_origin message + * + * @return Longitude (WGS84), expressed as * 1E7 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from gps_global_origin message + * + * @return Altitude(WGS84), expressed as * 1000 + */ +static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a gps_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); + gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); + gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); +#else + memcpy(gps_global_origin, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw.h new file mode 100644 index 0000000000..eb6ca89c5e --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw.h @@ -0,0 +1,342 @@ +// MESSAGE GPS_RAW PACKING + +#define MAVLINK_MSG_ID_GPS_RAW 32 + +typedef struct __mavlink_gps_raw_t +{ + uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float lat; ///< Latitude in degrees + float lon; ///< Longitude in degrees + float alt; ///< Altitude in meters + float eph; ///< GPS HDOP + float epv; ///< GPS VDOP + float v; ///< GPS ground speed + float hdg; ///< Compass heading in degrees, 0..360 degrees + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + uint8_t satellites_visible; ///< Number of satellites visible +} mavlink_gps_raw_t; + +#define MAVLINK_MSG_ID_GPS_RAW_LEN 38 +#define MAVLINK_MSG_ID_32_LEN 38 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RAW { \ + "GPS_RAW", \ + 10, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gps_raw_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gps_raw_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gps_raw_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_raw_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_raw_t, epv) }, \ + { "v", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_raw_t, v) }, \ + { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_raw_t, hdg) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_gps_raw_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_gps_raw_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a gps_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + * @param satellites_visible Number of satellites visible + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[38]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, eph); + _mav_put_float(buf, 24, epv); + _mav_put_float(buf, 28, v); + _mav_put_float(buf, 32, hdg); + _mav_put_uint8_t(buf, 36, fix_type); + _mav_put_uint8_t(buf, 37, satellites_visible); + + memcpy(_MAV_PAYLOAD(msg), buf, 38); +#else + mavlink_gps_raw_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.v = v; + packet.hdg = hdg; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD(msg), &packet, 38); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 38, 198); +} + +/** + * @brief Pack a gps_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + * @param satellites_visible Number of satellites visible + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,uint8_t fix_type,float lat,float lon,float alt,float eph,float epv,float v,float hdg,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[38]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, eph); + _mav_put_float(buf, 24, epv); + _mav_put_float(buf, 28, v); + _mav_put_float(buf, 32, hdg); + _mav_put_uint8_t(buf, 36, fix_type); + _mav_put_uint8_t(buf, 37, satellites_visible); + + memcpy(_MAV_PAYLOAD(msg), buf, 38); +#else + mavlink_gps_raw_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.v = v; + packet.hdg = hdg; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD(msg), &packet, 38); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 38, 198); +} + +/** + * @brief Encode a gps_raw struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw) +{ + return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg, gps_raw->satellites_visible); +} + +/** + * @brief Send a gps_raw message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in degrees + * @param lon Longitude in degrees + * @param alt Altitude in meters + * @param eph GPS HDOP + * @param epv GPS VDOP + * @param v GPS ground speed + * @param hdg Compass heading in degrees, 0..360 degrees + * @param satellites_visible Number of satellites visible + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[38]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, lat); + _mav_put_float(buf, 12, lon); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, eph); + _mav_put_float(buf, 24, epv); + _mav_put_float(buf, 28, v); + _mav_put_float(buf, 32, hdg); + _mav_put_uint8_t(buf, 36, fix_type); + _mav_put_uint8_t(buf, 37, satellites_visible); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, buf, 38, 198); +#else + mavlink_gps_raw_t packet; + packet.usec = usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.v = v; + packet.hdg = hdg; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, (const char *)&packet, 38, 198); +#endif +} + +#endif + +// MESSAGE GPS_RAW UNPACKING + + +/** + * @brief Get field usec from gps_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps_raw message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field lat from gps_raw message + * + * @return Latitude in degrees + */ +static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field lon from gps_raw message + * + * @return Longitude in degrees + */ +static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field alt from gps_raw message + * + * @return Altitude in meters + */ +static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field eph from gps_raw message + * + * @return GPS HDOP + */ +static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field epv from gps_raw message + * + * @return GPS VDOP + */ +static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field v from gps_raw message + * + * @return GPS ground speed + */ +static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field hdg from gps_raw message + * + * @return Compass heading in degrees, 0..360 degrees + */ +static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field satellites_visible from gps_raw message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_raw_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Decode a gps_raw message into a struct + * + * @param msg The message to decode + * @param gps_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg); + gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg); + gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg); + gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg); + gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg); + gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg); + gps_raw->v = mavlink_msg_gps_raw_get_v(msg); + gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg); + gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg); + gps_raw->satellites_visible = mavlink_msg_gps_raw_get_satellites_visible(msg); +#else + memcpy(gps_raw, _MAV_PAYLOAD(msg), 38); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h new file mode 100644 index 0000000000..866ada26e4 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_raw_int.h @@ -0,0 +1,342 @@ +// MESSAGE GPS_RAW_INT PACKING + +#define MAVLINK_MSG_ID_GPS_RAW_INT 24 + +typedef struct __mavlink_gps_raw_int_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int32_t lat; ///< Latitude in 1E7 degrees + int32_t lon; ///< Longitude in 1E7 degrees + int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL + uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535 + uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 +} mavlink_gps_raw_int_t; + +#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 +#define MAVLINK_MSG_ID_24_LEN 30 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ + "GPS_RAW_INT", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ + { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ + { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ + { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ + { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ + { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ + { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ + } \ +} + + +/** + * @brief Pack a gps_raw_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + return mavlink_finalize_message(msg, system_id, component_id, 30, 24); +} + +/** + * @brief Pack a gps_raw_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 24); +} + +/** + * @brief Encode a gps_raw_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_raw_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) +{ + return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); +} + +/** + * @brief Send a gps_raw_int message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param lat Latitude in 1E7 degrees + * @param lon Longitude in 1E7 degrees + * @param alt Altitude in 1E3 meters (millimeters) above MSL + * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 + * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + * @param satellites_visible Number of satellites visible. If unknown, set to 255 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lon); + _mav_put_int32_t(buf, 16, alt); + _mav_put_uint16_t(buf, 20, eph); + _mav_put_uint16_t(buf, 22, epv); + _mav_put_uint16_t(buf, 24, vel); + _mav_put_uint16_t(buf, 26, cog); + _mav_put_uint8_t(buf, 28, fix_type); + _mav_put_uint8_t(buf, 29, satellites_visible); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 30, 24); +#else + mavlink_gps_raw_int_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.eph = eph; + packet.epv = epv; + packet.vel = vel; + packet.cog = cog; + packet.fix_type = fix_type; + packet.satellites_visible = satellites_visible; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 30, 24); +#endif +} + +#endif + +// MESSAGE GPS_RAW_INT UNPACKING + + +/** + * @brief Get field time_usec from gps_raw_int message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field fix_type from gps_raw_int message + * + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field lat from gps_raw_int message + * + * @return Latitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lon from gps_raw_int message + * + * @return Longitude in 1E7 degrees + */ +static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from gps_raw_int message + * + * @return Altitude in 1E3 meters (millimeters) above MSL + */ +static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field eph from gps_raw_int message + * + * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field epv from gps_raw_int message + * + * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field vel from gps_raw_int message + * + * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field cog from gps_raw_int message + * + * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + */ +static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field satellites_visible from gps_raw_int message + * + * @return Number of satellites visible. If unknown, set to 255 + */ +static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Decode a gps_raw_int message into a struct + * + * @param msg The message to decode + * @param gps_raw_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); + gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); + gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); + gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); + gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); + gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); + gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); + gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); + gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); + gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); +#else + memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 30); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_set_global_origin.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_set_global_origin.h new file mode 100644 index 0000000000..97ce149078 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_set_global_origin.h @@ -0,0 +1,232 @@ +// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_gps_set_global_origin_t +{ + int32_t latitude; ///< global position * 1E7 + int32_t longitude; ///< global position * 1E7 + int32_t altitude; ///< global position * 1000 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_gps_set_global_origin_t; + +#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN 14 +#define MAVLINK_MSG_ID_48_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN { \ + "GPS_SET_GLOBAL_ORIGIN", \ + 5, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a gps_set_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_gps_set_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; + return mavlink_finalize_message(msg, system_id, component_id, 14, 170); +} + +/** + * @brief Pack a gps_set_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_gps_set_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 170); +} + +/** + * @brief Encode a gps_set_global_origin struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_set_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin) +{ + return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude); +} + +/** + * @brief Send a gps_set_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, buf, 14, 170); +#else + mavlink_gps_set_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, (const char *)&packet, 14, 170); +#endif +} + +#endif + +// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field target_system from gps_set_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from gps_set_global_origin message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Get field latitude from gps_set_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from gps_set_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from gps_set_global_origin message + * + * @return global position * 1000 + */ +static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a gps_set_global_origin message into a struct + * + * @param msg The message to decode + * @param gps_set_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg); + gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg); + gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg); + gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg); + gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg); +#else + memcpy(gps_set_global_origin, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h new file mode 100644 index 0000000000..f363daa96a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_gps_status.h @@ -0,0 +1,252 @@ +// MESSAGE GPS_STATUS PACKING + +#define MAVLINK_MSG_ID_GPS_STATUS 25 + +typedef struct __mavlink_gps_status_t +{ + uint8_t satellites_visible; ///< Number of satellites visible + uint8_t satellite_prn[20]; ///< Global satellite ID + uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization + uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite +} mavlink_gps_status_t; + +#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 +#define MAVLINK_MSG_ID_25_LEN 101 + +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 +#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 + +#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ + "GPS_STATUS", \ + 6, \ + { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ + { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ + { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ + { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ + { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ + { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ + } \ +} + + +/** + * @brief Pack a gps_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD(msg), buf, 101); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD(msg), &packet, 101); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 101, 23); +} + +/** + * @brief Pack a gps_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + memcpy(_MAV_PAYLOAD(msg), buf, 101); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + memcpy(_MAV_PAYLOAD(msg), &packet, 101); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23); +} + +/** + * @brief Encode a gps_status struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) +{ + return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); +} + +/** + * @brief Send a gps_status message + * @param chan MAVLink channel to send the message + * + * @param satellites_visible Number of satellites visible + * @param satellite_prn Global satellite ID + * @param satellite_used 0: Satellite not used, 1: used for localization + * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite + * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. + * @param satellite_snr Signal to noise ratio of satellite + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[101]; + _mav_put_uint8_t(buf, 0, satellites_visible); + _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); + _mav_put_uint8_t_array(buf, 21, satellite_used, 20); + _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); + _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); + _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23); +#else + mavlink_gps_status_t packet; + packet.satellites_visible = satellites_visible; + memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); + memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); + memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); + memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); + memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23); +#endif +} + +#endif + +// MESSAGE GPS_STATUS UNPACKING + + +/** + * @brief Get field satellites_visible from gps_status message + * + * @return Number of satellites visible + */ +static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field satellite_prn from gps_status message + * + * @return Global satellite ID + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); +} + +/** + * @brief Get field satellite_used from gps_status message + * + * @return 0: Satellite not used, 1: used for localization + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); +} + +/** + * @brief Get field satellite_elevation from gps_status message + * + * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); +} + +/** + * @brief Get field satellite_azimuth from gps_status message + * + * @return Direction of satellite, 0: 0 deg, 255: 360 deg. + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); +} + +/** + * @brief Get field satellite_snr from gps_status message + * + * @return Signal to noise ratio of satellite + */ +static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) +{ + return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); +} + +/** + * @brief Decode a gps_status message into a struct + * + * @param msg The message to decode + * @param gps_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); + mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); + mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); + mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); + mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); + mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); +#else + memcpy(gps_status, _MAV_PAYLOAD(msg), 101); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000..d194f21277 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_heartbeat.h @@ -0,0 +1,251 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + uint8_t autopilot; ///< Autopilot type / class. defined in MAV_CLASS ENUM + uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM + uint8_t mavlink_version; ///< MAVLink version +} mavlink_heartbeat_t; + +#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 +#define MAVLINK_MSG_ID_0_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ + "HEARTBEAT", \ + 6, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + } \ +} + + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message(msg, system_id, component_id, 9, 50); +} + +/** + * @brief Pack a heartbeat message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50); +} + +/** + * @brief Encode a heartbeat struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 3); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 3; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50); +#endif +} + +#endif + +// MESSAGE HEARTBEAT UNPACKING + + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Autopilot type / class. defined in MAV_CLASS ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field base_mode from heartbeat message + * + * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field custom_mode from heartbeat message + * + * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + */ +static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field system_status from heartbeat message + * + * @return System status flag, see MAV_STATUS ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); + heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +#else + memcpy(heartbeat, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h new file mode 100644 index 0000000000..23c84bc562 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_controls.h @@ -0,0 +1,364 @@ +// MESSAGE HIL_CONTROLS PACKING + +#define MAVLINK_MSG_ID_HIL_CONTROLS 91 + +typedef struct __mavlink_hil_controls_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float roll_ailerons; ///< Control output -1 .. 1 + float pitch_elevator; ///< Control output -1 .. 1 + float yaw_rudder; ///< Control output -1 .. 1 + float throttle; ///< Throttle 0 .. 1 + float aux1; ///< Aux 1, -1 .. 1 + float aux2; ///< Aux 2, -1 .. 1 + float aux3; ///< Aux 3, -1 .. 1 + float aux4; ///< Aux 4, -1 .. 1 + uint8_t mode; ///< System mode (MAV_MODE) + uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE) +} mavlink_hil_controls_t; + +#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 +#define MAVLINK_MSG_ID_91_LEN 42 + + + +#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ + "HIL_CONTROLS", \ + 11, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ + { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ + { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ + { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ + { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ + { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ + { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ + { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ + { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ + { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ + } \ +} + + +/** + * @brief Pack a hil_controls message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; + return mavlink_finalize_message(msg, system_id, component_id, 42, 63); +} + +/** + * @brief Pack a hil_controls message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 63); +} + +/** + * @brief Encode a hil_controls struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_controls C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) +{ + return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); +} + +/** + * @brief Send a hil_controls message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll_ailerons Control output -1 .. 1 + * @param pitch_elevator Control output -1 .. 1 + * @param yaw_rudder Control output -1 .. 1 + * @param throttle Throttle 0 .. 1 + * @param aux1 Aux 1, -1 .. 1 + * @param aux2 Aux 2, -1 .. 1 + * @param aux3 Aux 3, -1 .. 1 + * @param aux4 Aux 4, -1 .. 1 + * @param mode System mode (MAV_MODE) + * @param nav_mode Navigation mode (MAV_NAV_MODE) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll_ailerons); + _mav_put_float(buf, 12, pitch_elevator); + _mav_put_float(buf, 16, yaw_rudder); + _mav_put_float(buf, 20, throttle); + _mav_put_float(buf, 24, aux1); + _mav_put_float(buf, 28, aux2); + _mav_put_float(buf, 32, aux3); + _mav_put_float(buf, 36, aux4); + _mav_put_uint8_t(buf, 40, mode); + _mav_put_uint8_t(buf, 41, nav_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 42, 63); +#else + mavlink_hil_controls_t packet; + packet.time_usec = time_usec; + packet.roll_ailerons = roll_ailerons; + packet.pitch_elevator = pitch_elevator; + packet.yaw_rudder = yaw_rudder; + packet.throttle = throttle; + packet.aux1 = aux1; + packet.aux2 = aux2; + packet.aux3 = aux3; + packet.aux4 = aux4; + packet.mode = mode; + packet.nav_mode = nav_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 42, 63); +#endif +} + +#endif + +// MESSAGE HIL_CONTROLS UNPACKING + + +/** + * @brief Get field time_usec from hil_controls message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll_ailerons from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch_elevator from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw_rudder from hil_controls message + * + * @return Control output -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field throttle from hil_controls message + * + * @return Throttle 0 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field aux1 from hil_controls message + * + * @return Aux 1, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field aux2 from hil_controls message + * + * @return Aux 2, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field aux3 from hil_controls message + * + * @return Aux 3, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field aux4 from hil_controls message + * + * @return Aux 4, -1 .. 1 + */ +static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field mode from hil_controls message + * + * @return System mode (MAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Get field nav_mode from hil_controls message + * + * @return Navigation mode (MAV_NAV_MODE) + */ +static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 41); +} + +/** + * @brief Decode a hil_controls message into a struct + * + * @param msg The message to decode + * @param hil_controls C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); + hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); + hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); + hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); + hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); + hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); + hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); + hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); + hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); + hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); + hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); +#else + memcpy(hil_controls, _MAV_PAYLOAD(msg), 42); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h new file mode 100644 index 0000000000..d02c415397 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_rc_inputs_raw.h @@ -0,0 +1,430 @@ +// MESSAGE HIL_RC_INPUTS_RAW PACKING + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 + +typedef struct __mavlink_hil_rc_inputs_raw_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint16_t chan9_raw; ///< RC channel 9 value, in microseconds + uint16_t chan10_raw; ///< RC channel 10 value, in microseconds + uint16_t chan11_raw; ///< RC channel 11 value, in microseconds + uint16_t chan12_raw; ///< RC channel 12 value, in microseconds + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_hil_rc_inputs_raw_t; + +#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 +#define MAVLINK_MSG_ID_92_LEN 33 + + + +#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ + "HIL_RC_INPUTS_RAW", \ + 14, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ + { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ + { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ + { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ + { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a hil_rc_inputs_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 33); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 33, 54); +} + +/** + * @brief Pack a hil_rc_inputs_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 33); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 33); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 54); +} + +/** + * @brief Encode a hil_rc_inputs_raw struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_rc_inputs_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ + return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); +} + +/** + * @brief Send a hil_rc_inputs_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param chan9_raw RC channel 9 value, in microseconds + * @param chan10_raw RC channel 10 value, in microseconds + * @param chan11_raw RC channel 11 value, in microseconds + * @param chan12_raw RC channel 12 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[33]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 8, chan1_raw); + _mav_put_uint16_t(buf, 10, chan2_raw); + _mav_put_uint16_t(buf, 12, chan3_raw); + _mav_put_uint16_t(buf, 14, chan4_raw); + _mav_put_uint16_t(buf, 16, chan5_raw); + _mav_put_uint16_t(buf, 18, chan6_raw); + _mav_put_uint16_t(buf, 20, chan7_raw); + _mav_put_uint16_t(buf, 22, chan8_raw); + _mav_put_uint16_t(buf, 24, chan9_raw); + _mav_put_uint16_t(buf, 26, chan10_raw); + _mav_put_uint16_t(buf, 28, chan11_raw); + _mav_put_uint16_t(buf, 30, chan12_raw); + _mav_put_uint8_t(buf, 32, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, 33, 54); +#else + mavlink_hil_rc_inputs_raw_t packet; + packet.time_usec = time_usec; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.chan9_raw = chan9_raw; + packet.chan10_raw = chan10_raw; + packet.chan11_raw = chan11_raw; + packet.chan12_raw = chan12_raw; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, 33, 54); +#endif +} + +#endif + +// MESSAGE HIL_RC_INPUTS_RAW UNPACKING + + +/** + * @brief Get field time_usec from hil_rc_inputs_raw message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field chan1_raw from hil_rc_inputs_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan2_raw from hil_rc_inputs_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan3_raw from hil_rc_inputs_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan4_raw from hil_rc_inputs_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan5_raw from hil_rc_inputs_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan6_raw from hil_rc_inputs_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field chan7_raw from hil_rc_inputs_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field chan8_raw from hil_rc_inputs_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field chan9_raw from hil_rc_inputs_raw message + * + * @return RC channel 9 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field chan10_raw from hil_rc_inputs_raw message + * + * @return RC channel 10 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field chan11_raw from hil_rc_inputs_raw message + * + * @return RC channel 11 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field chan12_raw from hil_rc_inputs_raw message + * + * @return RC channel 12 value, in microseconds + */ +static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 30); +} + +/** + * @brief Get field rssi from hil_rc_inputs_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Decode a hil_rc_inputs_raw message into a struct + * + * @param msg The message to decode + * @param hil_rc_inputs_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); + hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); + hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); + hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); + hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); + hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); + hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); + hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); + hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); + hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); + hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); + hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); + hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); + hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); +#else + memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), 33); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h new file mode 100644 index 0000000000..f61c5170fd --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_hil_state.h @@ -0,0 +1,474 @@ +// MESSAGE HIL_STATE PACKING + +#define MAVLINK_MSG_ID_HIL_STATE 90 + +typedef struct __mavlink_hil_state_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float roll; ///< Roll angle (rad) + float pitch; ///< Pitch angle (rad) + float yaw; ///< Yaw angle (rad) + float rollspeed; ///< Roll angular speed (rad/s) + float pitchspeed; ///< Pitch angular speed (rad/s) + float yawspeed; ///< Yaw angular speed (rad/s) + int32_t lat; ///< Latitude, expressed as * 1E7 + int32_t lon; ///< Longitude, expressed as * 1E7 + int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) + int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 + int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 + int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) +} mavlink_hil_state_t; + +#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 +#define MAVLINK_MSG_ID_90_LEN 56 + + + +#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ + "HIL_STATE", \ + 16, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ + { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ + { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ + { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ + } \ +} + + +/** + * @brief Pack a hil_state message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD(msg), buf, 56); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD(msg), &packet, 56); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; + return mavlink_finalize_message(msg, system_id, component_id, 56, 183); +} + +/** + * @brief Pack a hil_state message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + memcpy(_MAV_PAYLOAD(msg), buf, 56); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + memcpy(_MAV_PAYLOAD(msg), &packet, 56); +#endif + + msg->msgid = MAVLINK_MSG_ID_HIL_STATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183); +} + +/** + * @brief Encode a hil_state struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param hil_state C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) +{ + return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); +} + +/** + * @brief Send a hil_state message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param roll Roll angle (rad) + * @param pitch Pitch angle (rad) + * @param yaw Yaw angle (rad) + * @param rollspeed Roll angular speed (rad/s) + * @param pitchspeed Pitch angular speed (rad/s) + * @param yawspeed Yaw angular speed (rad/s) + * @param lat Latitude, expressed as * 1E7 + * @param lon Longitude, expressed as * 1E7 + * @param alt Altitude in meters, expressed as * 1000 (millimeters) + * @param vx Ground X Speed (Latitude), expressed as m/s * 100 + * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 + * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[56]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, roll); + _mav_put_float(buf, 12, pitch); + _mav_put_float(buf, 16, yaw); + _mav_put_float(buf, 20, rollspeed); + _mav_put_float(buf, 24, pitchspeed); + _mav_put_float(buf, 28, yawspeed); + _mav_put_int32_t(buf, 32, lat); + _mav_put_int32_t(buf, 36, lon); + _mav_put_int32_t(buf, 40, alt); + _mav_put_int16_t(buf, 44, vx); + _mav_put_int16_t(buf, 46, vy); + _mav_put_int16_t(buf, 48, vz); + _mav_put_int16_t(buf, 50, xacc); + _mav_put_int16_t(buf, 52, yacc); + _mav_put_int16_t(buf, 54, zacc); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183); +#else + mavlink_hil_state_t packet; + packet.time_usec = time_usec; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.rollspeed = rollspeed; + packet.pitchspeed = pitchspeed; + packet.yawspeed = yawspeed; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183); +#endif +} + +#endif + +// MESSAGE HIL_STATE UNPACKING + + +/** + * @brief Get field time_usec from hil_state message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field roll from hil_state message + * + * @return Roll angle (rad) + */ +static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field pitch from hil_state message + * + * @return Pitch angle (rad) + */ +static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yaw from hil_state message + * + * @return Yaw angle (rad) + */ +static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field rollspeed from hil_state message + * + * @return Roll angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitchspeed from hil_state message + * + * @return Pitch angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yawspeed from hil_state message + * + * @return Yaw angular speed (rad/s) + */ +static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field lat from hil_state message + * + * @return Latitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 32); +} + +/** + * @brief Get field lon from hil_state message + * + * @return Longitude, expressed as * 1E7 + */ +static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 36); +} + +/** + * @brief Get field alt from hil_state message + * + * @return Altitude in meters, expressed as * 1000 (millimeters) + */ +static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 40); +} + +/** + * @brief Get field vx from hil_state message + * + * @return Ground X Speed (Latitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 44); +} + +/** + * @brief Get field vy from hil_state message + * + * @return Ground Y Speed (Longitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 46); +} + +/** + * @brief Get field vz from hil_state message + * + * @return Ground Z Speed (Altitude), expressed as m/s * 100 + */ +static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 48); +} + +/** + * @brief Get field xacc from hil_state message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 50); +} + +/** + * @brief Get field yacc from hil_state message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 52); +} + +/** + * @brief Get field zacc from hil_state message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 54); +} + +/** + * @brief Decode a hil_state message into a struct + * + * @param msg The message to decode + * @param hil_state C-struct to decode the message contents into + */ +static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) +{ +#if MAVLINK_NEED_BYTE_SWAP + hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); + hil_state->roll = mavlink_msg_hil_state_get_roll(msg); + hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); + hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); + hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); + hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); + hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); + hil_state->lat = mavlink_msg_hil_state_get_lat(msg); + hil_state->lon = mavlink_msg_hil_state_get_lon(msg); + hil_state->alt = mavlink_msg_hil_state_get_alt(msg); + hil_state->vx = mavlink_msg_hil_state_get_vx(msg); + hil_state->vy = mavlink_msg_hil_state_get_vy(msg); + hil_state->vz = mavlink_msg_hil_state_get_vz(msg); + hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); + hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); + hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); +#else + memcpy(hil_state, _MAV_PAYLOAD(msg), 56); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position.h new file mode 100644 index 0000000000..6ccb06a8d9 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position.h @@ -0,0 +1,286 @@ +// MESSAGE LOCAL_POSITION PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION 32 + +typedef struct __mavlink_local_position_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed +} mavlink_local_position_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_LEN 28 +#define MAVLINK_MSG_ID_32_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION { \ + "LOCAL_POSITION", \ + 7, \ +<<<<<<< HEAD + { { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_t, time_boot_ms) }, \ + { "x", MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_t, x) }, \ + { "y", MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_t, y) }, \ + { "z", MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_t, z) }, \ + { "vx", MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_t, vx) }, \ + { "vy", MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_t, vy) }, \ + { "vz", MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_t, vz) }, \ +======= + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_t, vz) }, \ +>>>>>>> 077b901fe072bb5fefdaca3680b3341c329395cb + } \ +} + + +/** + * @brief Pack a local_position message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_local_position_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; + return mavlink_finalize_message(msg, system_id, component_id, 28, 231); +} + +/** + * @brief Pack a local_position message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_local_position_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 231); +} + +/** + * @brief Encode a local_position struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position) +{ + return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->time_boot_ms, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz); +} + +/** + * @brief Send a local_position message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION, buf, 28, 231); +#else + mavlink_local_position_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION, (const char *)&packet, 28, 231); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_position message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_position message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_position message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position message into a struct + * + * @param msg The message to decode + * @param local_position C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position->time_boot_ms = mavlink_msg_local_position_get_time_boot_ms(msg); + local_position->x = mavlink_msg_local_position_get_x(msg); + local_position->y = mavlink_msg_local_position_get_y(msg); + local_position->z = mavlink_msg_local_position_get_z(msg); + local_position->vx = mavlink_msg_local_position_get_vx(msg); + local_position->vy = mavlink_msg_local_position_get_vy(msg); + local_position->vz = mavlink_msg_local_position_get_vz(msg); +#else + memcpy(local_position, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h new file mode 100644 index 0000000000..d59ae0b1a8 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_ned.h @@ -0,0 +1,276 @@ +// MESSAGE LOCAL_POSITION_NED PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 + +typedef struct __mavlink_local_position_ned_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + float vx; ///< X Speed + float vy; ///< Y Speed + float vz; ///< Z Speed +} mavlink_local_position_ned_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 +#define MAVLINK_MSG_ID_32_LEN 28 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ + "LOCAL_POSITION_NED", \ + 7, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ + } \ +} + + +/** + * @brief Pack a local_position_ned message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; + return mavlink_finalize_message(msg, system_id, component_id, 28, 185); +} + +/** + * @brief Pack a local_position_ned message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + memcpy(_MAV_PAYLOAD(msg), buf, 28); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + memcpy(_MAV_PAYLOAD(msg), &packet, 28); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 185); +} + +/** + * @brief Encode a local_position_ned struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_ned C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) +{ + return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); +} + +/** + * @brief Send a local_position_ned message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param vx X Speed + * @param vy Y Speed + * @param vz Z Speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[28]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, 28, 185); +#else + mavlink_local_position_ned_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, 28, 185); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION_NED UNPACKING + + +/** + * @brief Get field time_boot_ms from local_position_ned message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field x from local_position_ned message + * + * @return X Position + */ +static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_position_ned message + * + * @return Y Position + */ +static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_position_ned message + * + * @return Z Position + */ +static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_position_ned message + * + * @return X Speed + */ +static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_position_ned message + * + * @return Y Speed + */ +static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_position_ned message + * + * @return Z Speed + */ +static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a local_position_ned message into a struct + * + * @param msg The message to decode + * @param local_position_ned C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); + local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); + local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); + local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); + local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); + local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); + local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); +#else + memcpy(local_position_ned, _MAV_PAYLOAD(msg), 28); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h new file mode 100644 index 0000000000..7a83b16c6f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_local_position_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 + +typedef struct __mavlink_local_position_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU +} mavlink_local_position_setpoint_t; + +#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 +#define MAVLINK_MSG_ID_51_LEN 17 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \ + "LOCAL_POSITION_SETPOINT", \ + 5, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a local_position_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 17); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 17); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 17, 223); +} + +/** + * @brief Pack a local_position_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 17); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 17); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223); +} + +/** + * @brief Encode a local_position_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_position_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) +{ + return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); +} + +/** + * @brief Send a local_position_setpoint message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[17]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223); +#else + mavlink_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223); +#endif +} + +#endif + +// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING + + +/** + * @brief Get field coordinate_frame from local_position_setpoint message + * + * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + */ +static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field x from local_position_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from local_position_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from local_position_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from local_position_setpoint message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a local_position_setpoint message into a struct + * + * @param msg The message to decode + * @param local_position_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg); + local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg); + local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); + local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); + local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg); +#else + memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h new file mode 100644 index 0000000000..febb4535e2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_manual_control.h @@ -0,0 +1,320 @@ +// MESSAGE MANUAL_CONTROL PACKING + +#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 + +typedef struct __mavlink_manual_control_t +{ + float roll; ///< roll + float pitch; ///< pitch + float yaw; ///< yaw + float thrust; ///< thrust + uint8_t target; ///< The system to be controlled + uint8_t roll_manual; ///< roll control enabled auto:0, manual:1 + uint8_t pitch_manual; ///< pitch auto:0, manual:1 + uint8_t yaw_manual; ///< yaw auto:0, manual:1 + uint8_t thrust_manual; ///< thrust auto:0, manual:1 +} mavlink_manual_control_t; + +#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 21 +#define MAVLINK_MSG_ID_69_LEN 21 + + + +#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ + "MANUAL_CONTROL", \ + 9, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \ + { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \ + { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \ + { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \ + { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \ + } \ +} + + +/** + * @brief Pack a manual_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + memcpy(_MAV_PAYLOAD(msg), buf, 21); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + memcpy(_MAV_PAYLOAD(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 21, 52); +} + +/** + * @brief Pack a manual_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + memcpy(_MAV_PAYLOAD(msg), buf, 21); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + memcpy(_MAV_PAYLOAD(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 52); +} + +/** + * @brief Encode a manual_control struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param manual_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) +{ + return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual); +} + +/** + * @brief Send a manual_control message + * @param chan MAVLink channel to send the message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, 21, 52); +#else + mavlink_manual_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, 21, 52); +#endif +} + +#endif + +// MESSAGE MANUAL_CONTROL UNPACKING + + +/** + * @brief Get field target from manual_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field roll from manual_control message + * + * @return roll + */ +static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from manual_control message + * + * @return pitch + */ +static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from manual_control message + * + * @return yaw + */ +static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from manual_control message + * + * @return thrust + */ +static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll_manual from manual_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field pitch_manual from manual_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field yaw_manual from manual_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field thrust_manual from manual_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Decode a manual_control message into a struct + * + * @param msg The message to decode + * @param manual_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + manual_control->roll = mavlink_msg_manual_control_get_roll(msg); + manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg); + manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg); + manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg); + manual_control->target = mavlink_msg_manual_control_get_target(msg); + manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg); + manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg); + manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg); + manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg); +#else + memcpy(manual_control, _MAV_PAYLOAD(msg), 21); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h new file mode 100644 index 0000000000..fadb79ef98 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_memory_vect.h @@ -0,0 +1,204 @@ +// MESSAGE MEMORY_VECT PACKING + +#define MAVLINK_MSG_ID_MEMORY_VECT 249 + +typedef struct __mavlink_memory_vect_t +{ + uint16_t address; ///< Starting address of the debug variables + uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + uint8_t type; ///< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + int8_t value[32]; ///< Memory contents at specified address +} mavlink_memory_vect_t; + +#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 +#define MAVLINK_MSG_ID_249_LEN 36 + +#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 + +#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ + "MEMORY_VECT", \ + 4, \ + { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ + { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ + { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ + } \ +} + + +/** + * @brief Pack a memory_vect message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; + return mavlink_finalize_message(msg, system_id, component_id, 36, 204); +} + +/** + * @brief Pack a memory_vect message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + memcpy(packet.value, value, sizeof(int8_t)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 204); +} + +/** + * @brief Encode a memory_vect struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param memory_vect C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) +{ + return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); +} + +/** + * @brief Send a memory_vect message + * @param chan MAVLink channel to send the message + * + * @param address Starting address of the debug variables + * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + * @param value Memory contents at specified address + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_uint16_t(buf, 0, address); + _mav_put_uint8_t(buf, 2, ver); + _mav_put_uint8_t(buf, 3, type); + _mav_put_int8_t_array(buf, 4, value, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, 36, 204); +#else + mavlink_memory_vect_t packet; + packet.address = address; + packet.ver = ver; + packet.type = type; + memcpy(packet.value, value, sizeof(int8_t)*32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, 36, 204); +#endif +} + +#endif + +// MESSAGE MEMORY_VECT UNPACKING + + +/** + * @brief Get field address from memory_vect message + * + * @return Starting address of the debug variables + */ +static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field ver from memory_vect message + * + * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + */ +static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field type from memory_vect message + * + * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + */ +static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field value from memory_vect message + * + * @return Memory contents at specified address + */ +static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) +{ + return _MAV_RETURN_int8_t_array(msg, value, 32, 4); +} + +/** + * @brief Decode a memory_vect message into a struct + * + * @param msg The message to decode + * @param memory_vect C-struct to decode the message contents into + */ +static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) +{ +#if MAVLINK_NEED_BYTE_SWAP + memory_vect->address = mavlink_msg_memory_vect_get_address(msg); + memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); + memory_vect->type = mavlink_msg_memory_vect_get_type(msg); + mavlink_msg_memory_vect_get_value(msg, memory_vect->value); +#else + memcpy(memory_vect, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h new file mode 100644 index 0000000000..1696e76586 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_ack.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_ACK PACKING + +#define MAVLINK_MSG_ID_MISSION_ACK 47 + +typedef struct __mavlink_mission_ack_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t type; ///< See MAV_MISSION_RESULT enum +} mavlink_mission_ack_t; + +#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 +#define MAVLINK_MSG_ID_47_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ + "MISSION_ACK", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ + } \ +} + + +/** + * @brief Pack a mission_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 153); +} + +/** + * @brief Pack a mission_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 153); +} + +/** + * @brief Encode a mission_ack struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) +{ + return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); +} + +/** + * @brief Send a mission_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type See MAV_MISSION_RESULT enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, 3, 153); +#else + mavlink_mission_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, 3, 153); +#endif +} + +#endif + +// MESSAGE MISSION_ACK UNPACKING + + +/** + * @brief Get field target_system from mission_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field type from mission_ack message + * + * @return See MAV_MISSION_RESULT enum + */ +static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a mission_ack message into a struct + * + * @param msg The message to decode + * @param mission_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); + mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); + mission_ack->type = mavlink_msg_mission_ack_get_type(msg); +#else + memcpy(mission_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h new file mode 100644 index 0000000000..c421f57893 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_clear_all.h @@ -0,0 +1,166 @@ +// MESSAGE MISSION_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 + +typedef struct __mavlink_mission_clear_all_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_clear_all_t; + +#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 +#define MAVLINK_MSG_ID_45_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ + "MISSION_CLEAR_ALL", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_clear_all message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; + return mavlink_finalize_message(msg, system_id, component_id, 2, 232); +} + +/** + * @brief Pack a mission_clear_all message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 232); +} + +/** + * @brief Encode a mission_clear_all struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) +{ + return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); +} + +/** + * @brief Send a mission_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, 2, 232); +#else + mavlink_mission_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, 2, 232); +#endif +} + +#endif + +// MESSAGE MISSION_CLEAR_ALL UNPACKING + + +/** + * @brief Get field target_system from mission_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_clear_all message into a struct + * + * @param msg The message to decode + * @param mission_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); + mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); +#else + memcpy(mission_clear_all, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h new file mode 100644 index 0000000000..e93c1e8677 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_count.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_COUNT PACKING + +#define MAVLINK_MSG_ID_MISSION_COUNT 44 + +typedef struct __mavlink_mission_count_t +{ + uint16_t count; ///< Number of MISSIONs in the Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_count_t; + +#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 +#define MAVLINK_MSG_ID_44_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ + "MISSION_COUNT", \ + 3, \ + { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_count message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of MISSIONs in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 221); +} + +/** + * @brief Pack a mission_count message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param count Number of MISSIONs in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 221); +} + +/** + * @brief Encode a mission_count struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) +{ + return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); +} + +/** + * @brief Send a mission_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of MISSIONs in the Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, 4, 221); +#else + mavlink_mission_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, 4, 221); +#endif +} + +#endif + +// MESSAGE MISSION_COUNT UNPACKING + + +/** + * @brief Get field target_system from mission_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field count from mission_count message + * + * @return Number of MISSIONs in the Sequence + */ +static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_count message into a struct + * + * @param msg The message to decode + * @param mission_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_count->count = mavlink_msg_mission_count_get_count(msg); + mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); + mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); +#else + memcpy(mission_count, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h new file mode 100644 index 0000000000..2ad9fbc601 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_current.h @@ -0,0 +1,144 @@ +// MESSAGE MISSION_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_CURRENT 42 + +typedef struct __mavlink_mission_current_t +{ + uint16_t seq; ///< Sequence +} mavlink_mission_current_t; + +#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 +#define MAVLINK_MSG_ID_42_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ + "MISSION_CURRENT", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 2, 28); +} + +/** + * @brief Pack a mission_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 28); +} + +/** + * @brief Encode a mission_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) +{ + return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); +} + +/** + * @brief Send a mission_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, 2, 28); +#else + mavlink_mission_current_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, 2, 28); +#endif +} + +#endif + +// MESSAGE MISSION_CURRENT UNPACKING + + +/** + * @brief Get field seq from mission_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_current message into a struct + * + * @param msg The message to decode + * @param mission_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_current->seq = mavlink_msg_mission_current_get_seq(msg); +#else + memcpy(mission_current, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h new file mode 100644 index 0000000000..77f106cb01 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item.h @@ -0,0 +1,430 @@ +// MESSAGE MISSION_ITEM PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM 39 + +typedef struct __mavlink_mission_item_t +{ + float param1; ///< PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + float param2; ///< PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + float param3; ///< PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + float param4; ///< PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + float x; ///< PARAM5 / local: x position, global: latitude + float y; ///< PARAM6 / y position: global: longitude + float z; ///< PARAM7 / z position: global: altitude + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + uint8_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + uint8_t current; ///< false:0, true:1 + uint8_t autocontinue; ///< autocontinue to next wp +} mavlink_mission_item_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 36 +#define MAVLINK_MSG_ID_39_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ + "MISSION_ITEM", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_mission_item_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_mission_item_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a mission_item message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; + return mavlink_finalize_message(msg, system_id, component_id, 36, 158); +} + +/** + * @brief Pack a mission_item message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint8_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 158); +} + +/** + * @brief Encode a mission_item struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) +{ + return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); +} + +/** + * @brief Send a mission_item message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, 36, 158); +#else + mavlink_mission_item_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, 36, 158); +#endif +} + +#endif + +// MESSAGE MISSION_ITEM UNPACKING + + +/** + * @brief Get field target_system from mission_item message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from mission_item message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field seq from mission_item message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from mission_item message + * + * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field command from mission_item message + * + * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + */ +static inline uint8_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field current from mission_item message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field autocontinue from mission_item message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field param1 from mission_item message + * + * @return PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + */ +static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from mission_item message + * + * @return PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + */ +static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from mission_item message + * + * @return PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + */ +static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from mission_item message + * + * @return PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + */ +static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from mission_item message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field y from mission_item message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field z from mission_item message + * + * @return PARAM7 / z position: global: altitude + */ +static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a mission_item message into a struct + * + * @param msg The message to decode + * @param mission_item C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); + mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); + mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); + mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); + mission_item->x = mavlink_msg_mission_item_get_x(msg); + mission_item->y = mavlink_msg_mission_item_get_y(msg); + mission_item->z = mavlink_msg_mission_item_get_z(msg); + mission_item->seq = mavlink_msg_mission_item_get_seq(msg); + mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); + mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); + mission_item->frame = mavlink_msg_mission_item_get_frame(msg); + mission_item->command = mavlink_msg_mission_item_get_command(msg); + mission_item->current = mavlink_msg_mission_item_get_current(msg); + mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); +#else + memcpy(mission_item, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h new file mode 100644 index 0000000000..7d935cade2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_item_reached.h @@ -0,0 +1,144 @@ +// MESSAGE MISSION_ITEM_REACHED PACKING + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 + +typedef struct __mavlink_mission_item_reached_t +{ + uint16_t seq; ///< Sequence +} mavlink_mission_item_reached_t; + +#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 +#define MAVLINK_MSG_ID_46_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ + "MISSION_ITEM_REACHED", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a mission_item_reached message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; + return mavlink_finalize_message(msg, system_id, component_id, 2, 11); +} + +/** + * @brief Pack a mission_item_reached message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 11); +} + +/** + * @brief Encode a mission_item_reached struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_item_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) +{ + return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); +} + +/** + * @brief Send a mission_item_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, 2, 11); +#else + mavlink_mission_item_reached_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, 2, 11); +#endif +} + +#endif + +// MESSAGE MISSION_ITEM_REACHED UNPACKING + + +/** + * @brief Get field seq from mission_item_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_item_reached message into a struct + * + * @param msg The message to decode + * @param mission_item_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); +#else + memcpy(mission_item_reached, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h new file mode 100644 index 0000000000..5fb55ddb67 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_REQUEST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST 40 + +typedef struct __mavlink_mission_request_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_request_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 +#define MAVLINK_MSG_ID_40_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ + "MISSION_REQUEST", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; + return mavlink_finalize_message(msg, system_id, component_id, 4, 230); +} + +/** + * @brief Pack a mission_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 230); +} + +/** + * @brief Encode a mission_request struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) +{ + return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); +} + +/** + * @brief Send a mission_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, 4, 230); +#else + mavlink_mission_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, 4, 230); +#endif +} + +#endif + +// MESSAGE MISSION_REQUEST UNPACKING + + +/** + * @brief Get field target_system from mission_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_request message into a struct + * + * @param msg The message to decode + * @param mission_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request->seq = mavlink_msg_mission_request_get_seq(msg); + mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); + mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); +#else + memcpy(mission_request, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h new file mode 100644 index 0000000000..c41d0fa0b0 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_request_list.h @@ -0,0 +1,166 @@ +// MESSAGE MISSION_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 + +typedef struct __mavlink_mission_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_request_list_t; + +#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_43_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ + "MISSION_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 2, 132); +} + +/** + * @brief Pack a mission_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 132); +} + +/** + * @brief Encode a mission_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) +{ + return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); +} + +/** + * @brief Send a mission_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, 2, 132); +#else + mavlink_mission_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, 2, 132); +#endif +} + +#endif + +// MESSAGE MISSION_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from mission_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from mission_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a mission_request_list message into a struct + * + * @param msg The message to decode + * @param mission_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); + mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); +#else + memcpy(mission_request_list, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h new file mode 100644 index 0000000000..6fb6fd1cce --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_mission_set_current.h @@ -0,0 +1,188 @@ +// MESSAGE MISSION_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 + +typedef struct __mavlink_mission_set_current_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_mission_set_current_t; + +#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 +#define MAVLINK_MSG_ID_41_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ + "MISSION_SET_CURRENT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a mission_set_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 28); +} + +/** + * @brief Pack a mission_set_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 28); +} + +/** + * @brief Encode a mission_set_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mission_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) +{ + return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); +} + +/** + * @brief Send a mission_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, 4, 28); +#else + mavlink_mission_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, 4, 28); +#endif +} + +#endif + +// MESSAGE MISSION_SET_CURRENT UNPACKING + + +/** + * @brief Get field target_system from mission_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from mission_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from mission_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a mission_set_current message into a struct + * + * @param msg The message to decode + * @param mission_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); + mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); + mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); +#else + memcpy(mission_set_current, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h new file mode 100644 index 0000000000..c783558648 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_float.h @@ -0,0 +1,182 @@ +// MESSAGE NAMED_VALUE_FLOAT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 + +typedef struct __mavlink_named_value_float_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + float value; ///< Floating point value + char name[10]; ///< Name of the debug variable +} mavlink_named_value_float_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 +#define MAVLINK_MSG_ID_251_LEN 18 + +#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ + "NAMED_VALUE_FLOAT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_float message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + return mavlink_finalize_message(msg, system_id, component_id, 18, 170); +} + +/** + * @brief Pack a named_value_float message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 170); +} + +/** + * @brief Encode a named_value_float struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_float C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) +{ + return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); +} + +/** + * @brief Send a named_value_float message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Floating point value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 18, 170); +#else + mavlink_named_value_float_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 18, 170); +#endif +} + +#endif + +// MESSAGE NAMED_VALUE_FLOAT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_float message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_float message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_float message + * + * @return Floating point value + */ +static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Decode a named_value_float message into a struct + * + * @param msg The message to decode + * @param named_value_float C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); + named_value_float->value = mavlink_msg_named_value_float_get_value(msg); + mavlink_msg_named_value_float_get_name(msg, named_value_float->name); +#else + memcpy(named_value_float, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h new file mode 100644 index 0000000000..917f1efa0c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_named_value_int.h @@ -0,0 +1,182 @@ +// MESSAGE NAMED_VALUE_INT PACKING + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 + +typedef struct __mavlink_named_value_int_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int32_t value; ///< Signed integer value + char name[10]; ///< Name of the debug variable +} mavlink_named_value_int_t; + +#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 +#define MAVLINK_MSG_ID_252_LEN 18 + +#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 + +#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ + "NAMED_VALUE_INT", \ + 3, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ + { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ + } \ +} + + +/** + * @brief Pack a named_value_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + return mavlink_finalize_message(msg, system_id, component_id, 18, 44); +} + +/** + * @brief Pack a named_value_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,const char *name,int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44); +} + +/** + * @brief Encode a named_value_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param named_value_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) +{ + return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); +} + +/** + * @brief Send a named_value_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param name Name of the debug variable + * @param value Signed integer value + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, value); + _mav_put_char_array(buf, 8, name, 10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 18, 44); +#else + mavlink_named_value_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.value = value; + memcpy(packet.name, name, sizeof(char)*10); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 18, 44); +#endif +} + +#endif + +// MESSAGE NAMED_VALUE_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from named_value_int message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field name from named_value_int message + * + * @return Name of the debug variable + */ +static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 10, 8); +} + +/** + * @brief Get field value from named_value_int message + * + * @return Signed integer value + */ +static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Decode a named_value_int message into a struct + * + * @param msg The message to decode + * @param named_value_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); + named_value_int->value = mavlink_msg_named_value_int_get_value(msg); + mavlink_msg_named_value_int_get_name(msg, named_value_int->name); +#else + memcpy(named_value_int, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h new file mode 100644 index 0000000000..a8310c142b --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_nav_controller_output.h @@ -0,0 +1,298 @@ +// MESSAGE NAV_CONTROLLER_OUTPUT PACKING + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 + +typedef struct __mavlink_nav_controller_output_t +{ + float nav_roll; ///< Current desired roll in degrees + float nav_pitch; ///< Current desired pitch in degrees + float alt_error; ///< Current altitude error in meters + float aspd_error; ///< Current airspeed error in meters/second + float xtrack_error; ///< Current crosstrack error on x-y plane in meters + int16_t nav_bearing; ///< Current desired heading in degrees + int16_t target_bearing; ///< Bearing to current MISSION/target in degrees + uint16_t wp_dist; ///< Distance to active MISSION in meters +} mavlink_nav_controller_output_t; + +#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 +#define MAVLINK_MSG_ID_62_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ + "NAV_CONTROLLER_OUTPUT", \ + 8, \ + { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ + { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ + { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ + { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ + { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ + { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ + { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ + { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ + } \ +} + + +/** + * @brief Pack a nav_controller_output message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + return mavlink_finalize_message(msg, system_id, component_id, 26, 183); +} + +/** + * @brief Pack a nav_controller_output message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 183); +} + +/** + * @brief Encode a nav_controller_output struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param nav_controller_output C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) +{ + return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); +} + +/** + * @brief Send a nav_controller_output message + * @param chan MAVLink channel to send the message + * + * @param nav_roll Current desired roll in degrees + * @param nav_pitch Current desired pitch in degrees + * @param nav_bearing Current desired heading in degrees + * @param target_bearing Bearing to current MISSION/target in degrees + * @param wp_dist Distance to active MISSION in meters + * @param alt_error Current altitude error in meters + * @param aspd_error Current airspeed error in meters/second + * @param xtrack_error Current crosstrack error on x-y plane in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, nav_roll); + _mav_put_float(buf, 4, nav_pitch); + _mav_put_float(buf, 8, alt_error); + _mav_put_float(buf, 12, aspd_error); + _mav_put_float(buf, 16, xtrack_error); + _mav_put_int16_t(buf, 20, nav_bearing); + _mav_put_int16_t(buf, 22, target_bearing); + _mav_put_uint16_t(buf, 24, wp_dist); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, 26, 183); +#else + mavlink_nav_controller_output_t packet; + packet.nav_roll = nav_roll; + packet.nav_pitch = nav_pitch; + packet.alt_error = alt_error; + packet.aspd_error = aspd_error; + packet.xtrack_error = xtrack_error; + packet.nav_bearing = nav_bearing; + packet.target_bearing = target_bearing; + packet.wp_dist = wp_dist; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, 26, 183); +#endif +} + +#endif + +// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING + + +/** + * @brief Get field nav_roll from nav_controller_output message + * + * @return Current desired roll in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field nav_pitch from nav_controller_output message + * + * @return Current desired pitch in degrees + */ +static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field nav_bearing from nav_controller_output message + * + * @return Current desired heading in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field target_bearing from nav_controller_output message + * + * @return Bearing to current MISSION/target in degrees + */ +static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field wp_dist from nav_controller_output message + * + * @return Distance to active MISSION in meters + */ +static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field alt_error from nav_controller_output message + * + * @return Current altitude error in meters + */ +static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field aspd_error from nav_controller_output message + * + * @return Current airspeed error in meters/second + */ +static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field xtrack_error from nav_controller_output message + * + * @return Current crosstrack error on x-y plane in meters + */ +static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a nav_controller_output message into a struct + * + * @param msg The message to decode + * @param nav_controller_output C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) +{ +#if MAVLINK_NEED_BYTE_SWAP + nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); + nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); + nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); + nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); + nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); + nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); + nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); + nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); +#else + memcpy(nav_controller_output, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h new file mode 100644 index 0000000000..cebc1d9023 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_optical_flow.h @@ -0,0 +1,254 @@ +// MESSAGE OPTICAL_FLOW PACKING + +#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 + +typedef struct __mavlink_optical_flow_t +{ + uint64_t time_usec; ///< Timestamp (UNIX) + float ground_distance; ///< Ground distance in meters + int16_t flow_x; ///< Flow in pixels in x-sensor direction + int16_t flow_y; ///< Flow in pixels in y-sensor direction + uint8_t sensor_id; ///< Sensor ID + uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality +} mavlink_optical_flow_t; + +#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 18 +#define MAVLINK_MSG_ID_100_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ + "OPTICAL_FLOW", \ + 6, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ + { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, ground_distance) }, \ + { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_optical_flow_t, flow_x) }, \ + { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_optical_flow_t, flow_y) }, \ + { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_optical_flow_t, sensor_id) }, \ + { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_optical_flow_t, quality) }, \ + } \ +} + + +/** + * @brief Pack a optical_flow message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, ground_distance); + _mav_put_int16_t(buf, 12, flow_x); + _mav_put_int16_t(buf, 14, flow_y); + _mav_put_uint8_t(buf, 16, sensor_id); + _mav_put_uint8_t(buf, 17, quality); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; + return mavlink_finalize_message(msg, system_id, component_id, 18, 19); +} + +/** + * @brief Pack a optical_flow message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,uint8_t quality,float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, ground_distance); + _mav_put_int16_t(buf, 12, flow_x); + _mav_put_int16_t(buf, 14, flow_y); + _mav_put_uint8_t(buf, 16, sensor_id); + _mav_put_uint8_t(buf, 17, quality); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 19); +} + +/** + * @brief Encode a optical_flow struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param optical_flow C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) +{ + return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance); +} + +/** + * @brief Send a optical_flow message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (UNIX) + * @param sensor_id Sensor ID + * @param flow_x Flow in pixels in x-sensor direction + * @param flow_y Flow in pixels in y-sensor direction + * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality + * @param ground_distance Ground distance in meters + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, ground_distance); + _mav_put_int16_t(buf, 12, flow_x); + _mav_put_int16_t(buf, 14, flow_y); + _mav_put_uint8_t(buf, 16, sensor_id); + _mav_put_uint8_t(buf, 17, quality); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 18, 19); +#else + mavlink_optical_flow_t packet; + packet.time_usec = time_usec; + packet.ground_distance = ground_distance; + packet.flow_x = flow_x; + packet.flow_y = flow_y; + packet.sensor_id = sensor_id; + packet.quality = quality; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 18, 19); +#endif +} + +#endif + +// MESSAGE OPTICAL_FLOW UNPACKING + + +/** + * @brief Get field time_usec from optical_flow message + * + * @return Timestamp (UNIX) + */ +static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field sensor_id from optical_flow message + * + * @return Sensor ID + */ +static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field flow_x from optical_flow message + * + * @return Flow in pixels in x-sensor direction + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field flow_y from optical_flow message + * + * @return Flow in pixels in y-sensor direction + */ +static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field quality from optical_flow message + * + * @return Optical flow quality / confidence. 0: bad, 255: maximum quality + */ +static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field ground_distance from optical_flow message + * + * @return Ground distance in meters + */ +static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a optical_flow message into a struct + * + * @param msg The message to decode + * @param optical_flow C-struct to decode the message contents into + */ +static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) +{ +#if MAVLINK_NEED_BYTE_SWAP + optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); + optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); + optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); + optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); + optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); + optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); +#else + memcpy(optical_flow, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h new file mode 100644 index 0000000000..7ebd92284f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_list.h @@ -0,0 +1,166 @@ +// MESSAGE PARAM_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 + +typedef struct __mavlink_param_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_param_request_list_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_21_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ + "PARAM_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a param_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 2, 159); +} + +/** + * @brief Pack a param_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 159); +} + +/** + * @brief Encode a param_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) +{ + return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); +} + +/** + * @brief Send a param_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, 2, 159); +#else + mavlink_param_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, 2, 159); +#endif +} + +#endif + +// MESSAGE PARAM_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from param_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from param_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a param_request_list message into a struct + * + * @param msg The message to decode + * @param param_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); + param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); +#else + memcpy(param_request_list, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h new file mode 100644 index 0000000000..26965431ae --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_request_read.h @@ -0,0 +1,204 @@ +// MESSAGE PARAM_REQUEST_READ PACKING + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 + +typedef struct __mavlink_param_request_read_t +{ + int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + char param_id[16]; ///< Onboard parameter id +} mavlink_param_request_read_t; + +#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 +#define MAVLINK_MSG_ID_20_LEN 20 + +#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ + "PARAM_REQUEST_READ", \ + 4, \ + { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ + } \ +} + + +/** + * @brief Pack a param_request_read message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + return mavlink_finalize_message(msg, system_id, component_id, 20, 214); +} + +/** + * @brief Pack a param_request_read message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 214); +} + +/** + * @brief Encode a param_request_read struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_request_read C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) +{ + return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); +} + +/** + * @brief Send a param_request_read message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_index Parameter index. Send -1 to use the param ID field as identifier + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_int16_t(buf, 0, param_index); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_char_array(buf, 4, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 20, 214); +#else + mavlink_param_request_read_t packet; + packet.param_index = param_index; + packet.target_system = target_system; + packet.target_component = target_component; + memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 20, 214); +#endif +} + +#endif + +// MESSAGE PARAM_REQUEST_READ UNPACKING + + +/** + * @brief Get field target_system from param_request_read message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from param_request_read message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field param_id from param_request_read message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 4); +} + +/** + * @brief Get field param_index from param_request_read message + * + * @return Parameter index. Send -1 to use the param ID field as identifier + */ +static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 0); +} + +/** + * @brief Decode a param_request_read message into a struct + * + * @param msg The message to decode + * @param param_request_read C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); + param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); + param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); + mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); +#else + memcpy(param_request_read, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h new file mode 100644 index 0000000000..a463c69458 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_set.h @@ -0,0 +1,226 @@ +// MESSAGE PARAM_SET PACKING + +#define MAVLINK_MSG_ID_PARAM_SET 23 + +typedef struct __mavlink_param_set_t +{ + float param_value; ///< Onboard parameter value + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + char param_id[16]; ///< Onboard parameter id + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum +} mavlink_param_set_t; + +#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 +#define MAVLINK_MSG_ID_23_LEN 23 + +#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ + "PARAM_SET", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 23); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 23); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + return mavlink_finalize_message(msg, system_id, component_id, 23, 168); +} + +/** + * @brief Pack a param_set message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 23); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 23); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_SET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23, 168); +} + +/** + * @brief Encode a param_set struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) +{ + return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); +} + +/** + * @brief Send a param_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[23]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, target_component); + _mav_put_uint8_t(buf, 22, param_type); + _mav_put_char_array(buf, 6, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 23, 168); +#else + mavlink_param_set_t packet; + packet.param_value = param_value; + packet.target_system = target_system; + packet.target_component = target_component; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 23, 168); +#endif +} + +#endif + +// MESSAGE PARAM_SET UNPACKING + + +/** + * @brief Get field target_system from param_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field target_component from param_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field param_id from param_set message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 6); +} + +/** + * @brief Get field param_value from param_set message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_set message + * + * @return Onboard parameter type: see MAV_VAR enum + */ +static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 22); +} + +/** + * @brief Decode a param_set message into a struct + * + * @param msg The message to decode + * @param param_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_set->param_value = mavlink_msg_param_set_get_param_value(msg); + param_set->target_system = mavlink_msg_param_set_get_target_system(msg); + param_set->target_component = mavlink_msg_param_set_get_target_component(msg); + mavlink_msg_param_set_get_param_id(msg, param_set->param_id); + param_set->param_type = mavlink_msg_param_set_get_param_type(msg); +#else + memcpy(param_set, _MAV_PAYLOAD(msg), 23); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h new file mode 100644 index 0000000000..858921be39 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_param_value.h @@ -0,0 +1,226 @@ +// MESSAGE PARAM_VALUE PACKING + +#define MAVLINK_MSG_ID_PARAM_VALUE 22 + +typedef struct __mavlink_param_value_t +{ + float param_value; ///< Onboard parameter value + uint16_t param_count; ///< Total number of onboard parameters + uint16_t param_index; ///< Index of this onboard parameter + char param_id[16]; ///< Onboard parameter id + uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum +} mavlink_param_value_t; + +#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 +#define MAVLINK_MSG_ID_22_LEN 25 + +#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 + +#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ + "PARAM_VALUE", \ + 5, \ + { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ + { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ + { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ + { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ + { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ + } \ +} + + +/** + * @brief Pack a param_value message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 25); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + return mavlink_finalize_message(msg, system_id, component_id, 25, 220); +} + +/** + * @brief Pack a param_value message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + memcpy(_MAV_PAYLOAD(msg), buf, 25); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + memcpy(_MAV_PAYLOAD(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 220); +} + +/** + * @brief Encode a param_value struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param param_value C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) +{ + return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); +} + +/** + * @brief Send a param_value message + * @param chan MAVLink channel to send the message + * + * @param param_id Onboard parameter id + * @param param_value Onboard parameter value + * @param param_type Onboard parameter type: see MAV_VAR enum + * @param param_count Total number of onboard parameters + * @param param_index Index of this onboard parameter + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, param_value); + _mav_put_uint16_t(buf, 4, param_count); + _mav_put_uint16_t(buf, 6, param_index); + _mav_put_uint8_t(buf, 24, param_type); + _mav_put_char_array(buf, 8, param_id, 16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 25, 220); +#else + mavlink_param_value_t packet; + packet.param_value = param_value; + packet.param_count = param_count; + packet.param_index = param_index; + packet.param_type = param_type; + memcpy(packet.param_id, param_id, sizeof(char)*16); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 25, 220); +#endif +} + +#endif + +// MESSAGE PARAM_VALUE UNPACKING + + +/** + * @brief Get field param_id from param_value message + * + * @return Onboard parameter id + */ +static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) +{ + return _MAV_RETURN_char_array(msg, param_id, 16, 8); +} + +/** + * @brief Get field param_value from param_value message + * + * @return Onboard parameter value + */ +static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param_type from param_value message + * + * @return Onboard parameter type: see MAV_VAR enum + */ +static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field param_count from param_value message + * + * @return Total number of onboard parameters + */ +static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field param_index from param_value message + * + * @return Index of this onboard parameter + */ +static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Decode a param_value message into a struct + * + * @param msg The message to decode + * @param param_value C-struct to decode the message contents into + */ +static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) +{ +#if MAVLINK_NEED_BYTE_SWAP + param_value->param_value = mavlink_msg_param_value_get_param_value(msg); + param_value->param_count = mavlink_msg_param_value_get_param_count(msg); + param_value->param_index = mavlink_msg_param_value_get_param_index(msg); + mavlink_msg_param_value_get_param_id(msg, param_value->param_id); + param_value->param_type = mavlink_msg_param_value_get_param_type(msg); +#else + memcpy(param_value, _MAV_PAYLOAD(msg), 25); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h new file mode 100644 index 0000000000..8c4bf0cc8c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_ping.h @@ -0,0 +1,210 @@ +// MESSAGE PING PACKING + +#define MAVLINK_MSG_ID_PING 4 + +typedef struct __mavlink_ping_t +{ + uint64_t time_usec; ///< Unix timestamp in microseconds + uint32_t seq; ///< PING sequence + uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system +} mavlink_ping_t; + +#define MAVLINK_MSG_ID_PING_LEN 14 +#define MAVLINK_MSG_ID_4_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_PING { \ + "PING", \ + 4, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a ping message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; + return mavlink_finalize_message(msg, system_id, component_id, 14, 237); +} + +/** + * @brief Pack a ping message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_PING; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 237); +} + +/** + * @brief Encode a ping struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ping C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) +{ + return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); +} + +/** + * @brief Send a ping message + * @param chan MAVLink channel to send the message + * + * @param time_usec Unix timestamp in microseconds + * @param seq PING sequence + * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_uint8_t(buf, 12, target_system); + _mav_put_uint8_t(buf, 13, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14, 237); +#else + mavlink_ping_t packet; + packet.time_usec = time_usec; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14, 237); +#endif +} + +#endif + +// MESSAGE PING UNPACKING + + +/** + * @brief Get field time_usec from ping message + * + * @return Unix timestamp in microseconds + */ +static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from ping message + * + * @return PING sequence + */ +static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field target_system from ping message + * + * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field target_component from ping message + * + * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + */ +static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 13); +} + +/** + * @brief Decode a ping message into a struct + * + * @param msg The message to decode + * @param ping C-struct to decode the message contents into + */ +static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) +{ +#if MAVLINK_NEED_BYTE_SWAP + ping->time_usec = mavlink_msg_ping_get_time_usec(msg); + ping->seq = mavlink_msg_ping_get_seq(msg); + ping->target_system = mavlink_msg_ping_get_target_system(msg); + ping->target_component = mavlink_msg_ping_get_target_component(msg); +#else + memcpy(ping, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_position_target.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_position_target.h new file mode 100644 index 0000000000..44c0e6931b --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_position_target.h @@ -0,0 +1,210 @@ +// MESSAGE POSITION_TARGET PACKING + +#define MAVLINK_MSG_ID_POSITION_TARGET 63 + +typedef struct __mavlink_position_target_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH +} mavlink_position_target_t; + +#define MAVLINK_MSG_ID_POSITION_TARGET_LEN 16 +#define MAVLINK_MSG_ID_63_LEN 16 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_TARGET { \ + "POSITION_TARGET", \ + 4, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_target_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a position_target message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_position_target_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; + return mavlink_finalize_message(msg, system_id, component_id, 16, 126); +} + +/** + * @brief Pack a position_target message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_position_target_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 126); +} + +/** + * @brief Encode a position_target struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_target C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target) +{ + return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw); +} + +/** + * @brief Send a position_target message + * @param chan MAVLink channel to send the message + * + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET, buf, 16, 126); +#else + mavlink_position_target_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET, (const char *)&packet, 16, 126); +#endif +} + +#endif + +// MESSAGE POSITION_TARGET UNPACKING + + +/** + * @brief Get field x from position_target message + * + * @return x position + */ +static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from position_target message + * + * @return y position + */ +static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from position_target message + * + * @return z position + */ +static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from position_target message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a position_target message into a struct + * + * @param msg The message to decode + * @param position_target C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_target->x = mavlink_msg_position_target_get_x(msg); + position_target->y = mavlink_msg_position_target_get_y(msg); + position_target->z = mavlink_msg_position_target_get_z(msg); + position_target->yaw = mavlink_msg_position_target_get_yaw(msg); +#else + memcpy(position_target, _MAV_PAYLOAD(msg), 16); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h new file mode 100644 index 0000000000..a8c3988893 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_imu.h @@ -0,0 +1,342 @@ +// MESSAGE RAW_IMU PACKING + +#define MAVLINK_MSG_ID_RAW_IMU 27 + +typedef struct __mavlink_raw_imu_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t xacc; ///< X acceleration (raw) + int16_t yacc; ///< Y acceleration (raw) + int16_t zacc; ///< Z acceleration (raw) + int16_t xgyro; ///< Angular speed around X axis (raw) + int16_t ygyro; ///< Angular speed around Y axis (raw) + int16_t zgyro; ///< Angular speed around Z axis (raw) + int16_t xmag; ///< X Magnetic field (raw) + int16_t ymag; ///< Y Magnetic field (raw) + int16_t zmag; ///< Z Magnetic field (raw) +} mavlink_raw_imu_t; + +#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 +#define MAVLINK_MSG_ID_27_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ + "RAW_IMU", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a raw_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + return mavlink_finalize_message(msg, system_id, component_id, 26, 144); +} + +/** + * @brief Pack a raw_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_IMU; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 144); +} + +/** + * @brief Encode a raw_imu struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) +{ + return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); +} + +/** + * @brief Send a raw_imu message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param xacc X acceleration (raw) + * @param yacc Y acceleration (raw) + * @param zacc Z acceleration (raw) + * @param xgyro Angular speed around X axis (raw) + * @param ygyro Angular speed around Y axis (raw) + * @param zgyro Angular speed around Z axis (raw) + * @param xmag X Magnetic field (raw) + * @param ymag Y Magnetic field (raw) + * @param zmag Z Magnetic field (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, xacc); + _mav_put_int16_t(buf, 10, yacc); + _mav_put_int16_t(buf, 12, zacc); + _mav_put_int16_t(buf, 14, xgyro); + _mav_put_int16_t(buf, 16, ygyro); + _mav_put_int16_t(buf, 18, zgyro); + _mav_put_int16_t(buf, 20, xmag); + _mav_put_int16_t(buf, 22, ymag); + _mav_put_int16_t(buf, 24, zmag); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, 26, 144); +#else + mavlink_raw_imu_t packet; + packet.time_usec = time_usec; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, 26, 144); +#endif +} + +#endif + +// MESSAGE RAW_IMU UNPACKING + + +/** + * @brief Get field time_usec from raw_imu message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field xacc from raw_imu message + * + * @return X acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field yacc from raw_imu message + * + * @return Y acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field zacc from raw_imu message + * + * @return Z acceleration (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field xgyro from raw_imu message + * + * @return Angular speed around X axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field ygyro from raw_imu message + * + * @return Angular speed around Y axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field zgyro from raw_imu message + * + * @return Angular speed around Z axis (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field xmag from raw_imu message + * + * @return X Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Get field ymag from raw_imu message + * + * @return Y Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 22); +} + +/** + * @brief Get field zmag from raw_imu message + * + * @return Z Magnetic field (raw) + */ +static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 24); +} + +/** + * @brief Decode a raw_imu message into a struct + * + * @param msg The message to decode + * @param raw_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); + raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); + raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); + raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); + raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); + raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); + raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); + raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); + raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); + raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); +#else + memcpy(raw_imu, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h new file mode 100644 index 0000000000..29e631f39c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_raw_pressure.h @@ -0,0 +1,232 @@ +// MESSAGE RAW_PRESSURE PACKING + +#define MAVLINK_MSG_ID_RAW_PRESSURE 28 + +typedef struct __mavlink_raw_pressure_t +{ + uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + int16_t press_abs; ///< Absolute pressure (raw) + int16_t press_diff1; ///< Differential pressure 1 (raw) + int16_t press_diff2; ///< Differential pressure 2 (raw) + int16_t temperature; ///< Raw Temperature measurement (raw) +} mavlink_raw_pressure_t; + +#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 +#define MAVLINK_MSG_ID_28_LEN 16 + + + +#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ + "RAW_PRESSURE", \ + 5, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ + { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ + { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ + { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a raw_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; + return mavlink_finalize_message(msg, system_id, component_id, 16, 67); +} + +/** + * @brief Pack a raw_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 67); +} + +/** + * @brief Encode a raw_pressure struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) +{ + return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); +} + +/** + * @brief Send a raw_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (raw) + * @param press_diff1 Differential pressure 1 (raw) + * @param press_diff2 Differential pressure 2 (raw) + * @param temperature Raw Temperature measurement (raw) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int16_t(buf, 8, press_abs); + _mav_put_int16_t(buf, 10, press_diff1); + _mav_put_int16_t(buf, 12, press_diff2); + _mav_put_int16_t(buf, 14, temperature); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, 16, 67); +#else + mavlink_raw_pressure_t packet; + packet.time_usec = time_usec; + packet.press_abs = press_abs; + packet.press_diff1 = press_diff1; + packet.press_diff2 = press_diff2; + packet.temperature = temperature; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, 16, 67); +#endif +} + +#endif + +// MESSAGE RAW_PRESSURE UNPACKING + + +/** + * @brief Get field time_usec from raw_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field press_abs from raw_pressure message + * + * @return Absolute pressure (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field press_diff1 from raw_pressure message + * + * @return Differential pressure 1 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field press_diff2 from raw_pressure message + * + * @return Differential pressure 2 (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field temperature from raw_pressure message + * + * @return Raw Temperature measurement (raw) + */ +static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Decode a raw_pressure message into a struct + * + * @param msg The message to decode + * @param raw_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); + raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); + raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); + raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); + raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); +#else + memcpy(raw_pressure, _MAV_PAYLOAD(msg), 16); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h new file mode 100644 index 0000000000..6eccf7ae8d --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_override.h @@ -0,0 +1,342 @@ +// MESSAGE RC_CHANNELS_OVERRIDE PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 + +typedef struct __mavlink_rc_channels_override_t +{ + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_rc_channels_override_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 +#define MAVLINK_MSG_ID_70_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ + "RC_CHANNELS_OVERRIDE", \ + 10, \ + { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_override message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; + return mavlink_finalize_message(msg, system_id, component_id, 18, 124); +} + +/** + * @brief Pack a rc_channels_override message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 124); +} + +/** + * @brief Encode a rc_channels_override struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_override C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) +{ + return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); +} + +/** + * @brief Send a rc_channels_override message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_uint16_t(buf, 0, chan1_raw); + _mav_put_uint16_t(buf, 2, chan2_raw); + _mav_put_uint16_t(buf, 4, chan3_raw); + _mav_put_uint16_t(buf, 6, chan4_raw); + _mav_put_uint16_t(buf, 8, chan5_raw); + _mav_put_uint16_t(buf, 10, chan6_raw); + _mav_put_uint16_t(buf, 12, chan7_raw); + _mav_put_uint16_t(buf, 14, chan8_raw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, 18, 124); +#else + mavlink_rc_channels_override_t packet; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, 18, 124); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING + + +/** + * @brief Get field target_system from rc_channels_override message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from rc_channels_override message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field chan1_raw from rc_channels_override message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field chan2_raw from rc_channels_override message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field chan3_raw from rc_channels_override message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan4_raw from rc_channels_override message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan5_raw from rc_channels_override message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan6_raw from rc_channels_override message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan7_raw from rc_channels_override message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan8_raw from rc_channels_override message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Decode a rc_channels_override message into a struct + * + * @param msg The message to decode + * @param rc_channels_override C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); + rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); + rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); + rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); + rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); + rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); + rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); + rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); + rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); + rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); +#else + memcpy(rc_channels_override, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h new file mode 100644 index 0000000000..1c25d1a3b3 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_raw.h @@ -0,0 +1,364 @@ +// MESSAGE RC_CHANNELS_RAW PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 + +typedef struct __mavlink_rc_channels_raw_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + uint16_t chan1_raw; ///< RC channel 1 value, in microseconds + uint16_t chan2_raw; ///< RC channel 2 value, in microseconds + uint16_t chan3_raw; ///< RC channel 3 value, in microseconds + uint16_t chan4_raw; ///< RC channel 4 value, in microseconds + uint16_t chan5_raw; ///< RC channel 5 value, in microseconds + uint16_t chan6_raw; ///< RC channel 6 value, in microseconds + uint16_t chan7_raw; ///< RC channel 7 value, in microseconds + uint16_t chan8_raw; ///< RC channel 8 value, in microseconds + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_rc_channels_raw_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 +#define MAVLINK_MSG_ID_35_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ + "RC_CHANNELS_RAW", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ + { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ + { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ + { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ + { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ + { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ + { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ + { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ + { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 22, 244); +} + +/** + * @brief Pack a rc_channels_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 244); +} + +/** + * @brief Encode a rc_channels_raw struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) +{ + return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); +} + +/** + * @brief Send a rc_channels_raw message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_raw RC channel 1 value, in microseconds + * @param chan2_raw RC channel 2 value, in microseconds + * @param chan3_raw RC channel 3 value, in microseconds + * @param chan4_raw RC channel 4 value, in microseconds + * @param chan5_raw RC channel 5 value, in microseconds + * @param chan6_raw RC channel 6 value, in microseconds + * @param chan7_raw RC channel 7 value, in microseconds + * @param chan8_raw RC channel 8 value, in microseconds + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_uint16_t(buf, 4, chan1_raw); + _mav_put_uint16_t(buf, 6, chan2_raw); + _mav_put_uint16_t(buf, 8, chan3_raw); + _mav_put_uint16_t(buf, 10, chan4_raw); + _mav_put_uint16_t(buf, 12, chan5_raw); + _mav_put_uint16_t(buf, 14, chan6_raw); + _mav_put_uint16_t(buf, 16, chan7_raw); + _mav_put_uint16_t(buf, 18, chan8_raw); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 22, 244); +#else + mavlink_rc_channels_raw_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_raw = chan1_raw; + packet.chan2_raw = chan2_raw; + packet.chan3_raw = chan3_raw; + packet.chan4_raw = chan4_raw; + packet.chan5_raw = chan5_raw; + packet.chan6_raw = chan6_raw; + packet.chan7_raw = chan7_raw; + packet.chan8_raw = chan8_raw; + packet.port = port; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 22, 244); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_RAW UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_raw message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_raw from rc_channels_raw message + * + * @return RC channel 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field chan2_raw from rc_channels_raw message + * + * @return RC channel 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field chan3_raw from rc_channels_raw message + * + * @return RC channel 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field chan4_raw from rc_channels_raw message + * + * @return RC channel 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field chan5_raw from rc_channels_raw message + * + * @return RC channel 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field chan6_raw from rc_channels_raw message + * + * @return RC channel 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field chan7_raw from rc_channels_raw message + * + * @return RC channel 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field chan8_raw from rc_channels_raw message + * + * @return RC channel 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_raw message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_raw message into a struct + * + * @param msg The message to decode + * @param rc_channels_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); + rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); + rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); + rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); + rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); + rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); + rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); + rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); + rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); + rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); + rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); +#else + memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h new file mode 100644 index 0000000000..9a4a7912e2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_rc_channels_scaled.h @@ -0,0 +1,364 @@ +// MESSAGE RC_CHANNELS_SCALED PACKING + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 36 + +typedef struct __mavlink_rc_channels_scaled_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% +} mavlink_rc_channels_scaled_t; + +#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 +#define MAVLINK_MSG_ID_36_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ + "RC_CHANNELS_SCALED", \ + 11, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ + { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ + { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ + { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ + { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ + { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ + { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ + { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ + { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ + { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ + } \ +} + + +/** + * @brief Pack a rc_channels_scaled message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + return mavlink_finalize_message(msg, system_id, component_id, 22, 237); +} + +/** + * @brief Pack a rc_channels_scaled message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 237); +} + +/** + * @brief Encode a rc_channels_scaled struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param rc_channels_scaled C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ + return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); +} + +/** + * @brief Send a rc_channels_scaled message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, chan1_scaled); + _mav_put_int16_t(buf, 6, chan2_scaled); + _mav_put_int16_t(buf, 8, chan3_scaled); + _mav_put_int16_t(buf, 10, chan4_scaled); + _mav_put_int16_t(buf, 12, chan5_scaled); + _mav_put_int16_t(buf, 14, chan6_scaled); + _mav_put_int16_t(buf, 16, chan7_scaled); + _mav_put_int16_t(buf, 18, chan8_scaled); + _mav_put_uint8_t(buf, 20, port); + _mav_put_uint8_t(buf, 21, rssi); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 22, 237); +#else + mavlink_rc_channels_scaled_t packet; + packet.time_boot_ms = time_boot_ms; + packet.chan1_scaled = chan1_scaled; + packet.chan2_scaled = chan2_scaled; + packet.chan3_scaled = chan3_scaled; + packet.chan4_scaled = chan4_scaled; + packet.chan5_scaled = chan5_scaled; + packet.chan6_scaled = chan6_scaled; + packet.chan7_scaled = chan7_scaled; + packet.chan8_scaled = chan8_scaled; + packet.port = port; + packet.rssi = rssi; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 22, 237); +#endif +} + +#endif + +// MESSAGE RC_CHANNELS_SCALED UNPACKING + + +/** + * @brief Get field time_boot_ms from rc_channels_scaled message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from rc_channels_scaled message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field chan1_scaled from rc_channels_scaled message + * + * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field chan2_scaled from rc_channels_scaled message + * + * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field chan3_scaled from rc_channels_scaled message + * + * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field chan4_scaled from rc_channels_scaled message + * + * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field chan5_scaled from rc_channels_scaled message + * + * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field chan6_scaled from rc_channels_scaled message + * + * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field chan7_scaled from rc_channels_scaled message + * + * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field chan8_scaled from rc_channels_scaled message + * + * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + */ +static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field rssi from rc_channels_scaled message + * + * @return Receive signal strength indicator, 0: 0%, 255: 100% + */ +static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 21); +} + +/** + * @brief Decode a rc_channels_scaled message into a struct + * + * @param msg The message to decode + * @param rc_channels_scaled C-struct to decode the message contents into + */ +static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) +{ +#if MAVLINK_NEED_BYTE_SWAP + rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); + rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); + rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); + rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); + rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); + rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); + rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); + rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); + rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); + rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); + rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); +#else + memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h new file mode 100644 index 0000000000..9889bfc085 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_request_data_stream.h @@ -0,0 +1,232 @@ +// MESSAGE REQUEST_DATA_STREAM PACKING + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 + +typedef struct __mavlink_request_data_stream_t +{ + uint16_t req_message_rate; ///< The requested interval between two messages of this type + uint8_t target_system; ///< The target requested to send the message stream. + uint8_t target_component; ///< The target requested to send the message stream. + uint8_t req_stream_id; ///< The ID of the requested data stream + uint8_t start_stop; ///< 1 to start sending, 0 to stop sending. +} mavlink_request_data_stream_t; + +#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 +#define MAVLINK_MSG_ID_66_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ + "REQUEST_DATA_STREAM", \ + 5, \ + { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ + { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ + { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ + } \ +} + + +/** + * @brief Pack a request_data_stream message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + return mavlink_finalize_message(msg, system_id, component_id, 6, 148); +} + +/** + * @brief Pack a request_data_stream message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 148); +} + +/** + * @brief Encode a request_data_stream struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param request_data_stream C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) +{ + return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); +} + +/** + * @brief Send a request_data_stream message + * @param chan MAVLink channel to send the message + * + * @param target_system The target requested to send the message stream. + * @param target_component The target requested to send the message stream. + * @param req_stream_id The ID of the requested data stream + * @param req_message_rate The requested interval between two messages of this type + * @param start_stop 1 to start sending, 0 to stop sending. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, req_message_rate); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + _mav_put_uint8_t(buf, 4, req_stream_id); + _mav_put_uint8_t(buf, 5, start_stop); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6, 148); +#else + mavlink_request_data_stream_t packet; + packet.req_message_rate = req_message_rate; + packet.target_system = target_system; + packet.target_component = target_component; + packet.req_stream_id = req_stream_id; + packet.start_stop = start_stop; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6, 148); +#endif +} + +#endif + +// MESSAGE REQUEST_DATA_STREAM UNPACKING + + +/** + * @brief Get field target_system from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from request_data_stream message + * + * @return The target requested to send the message stream. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field req_stream_id from request_data_stream message + * + * @return The ID of the requested data stream + */ +static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field req_message_rate from request_data_stream message + * + * @return The requested interval between two messages of this type + */ +static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field start_stop from request_data_stream message + * + * @return 1 to start sending, 0 to stop sending. + */ +static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a request_data_stream message into a struct + * + * @param msg The message to decode + * @param request_data_stream C-struct to decode the message contents into + */ +static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) +{ +#if MAVLINK_NEED_BYTE_SWAP + request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); + request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); + request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); + request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); + request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); +#else + memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h new file mode 100644 index 0000000000..80a88cca2f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 + +typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll_speed; ///< Desired roll angular speed in rad/s + float pitch_speed; ///< Desired pitch angular speed in rad/s + float yaw_speed; ///< Desired yaw angular speed in rad/s + float thrust; ///< Collective thrust, normalized to 0 .. 1 +} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t; + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 +#define MAVLINK_MSG_ID_59_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ + "ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \ + 5, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \ + { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ + } \ +} + + +/** + * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 238); +} + +/** + * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238); +} + +/** + * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) +{ + return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust); +} + +/** + * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll_speed); + _mav_put_float(buf, 8, pitch_speed); + _mav_put_float(buf, 12, yaw_speed); + _mav_put_float(buf, 16, thrust); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 20, 238); +#else + mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 20, 238); +#endif +} + +#endif + +// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired roll angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired pitch angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Desired yaw angular speed in rad/s + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct + * + * @param msg The message to decode + * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg); + roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg); + roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg); +#else + memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h new file mode 100644 index 0000000000..b8b87028d5 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58 + +typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float roll; ///< Desired roll angle in radians + float pitch; ///< Desired pitch angle in radians + float yaw; ///< Desired yaw angle in radians + float thrust; ///< Collective thrust, normalized to 0 .. 1 +} mavlink_roll_pitch_yaw_thrust_setpoint_t; + +#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 +#define MAVLINK_MSG_ID_58_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \ + "ROLL_PITCH_YAW_THRUST_SETPOINT", \ + 5, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_boot_ms) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \ + } \ +} + + +/** + * @brief Pack a roll_pitch_yaw_thrust_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 20, 239); +} + +/** + * @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 239); +} + +/** + * @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) +{ + return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust); +} + +/** + * @brief Send a roll_pitch_yaw_thrust_setpoint message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, roll); + _mav_put_float(buf, 8, pitch); + _mav_put_float(buf, 12, yaw); + _mav_put_float(buf, 16, thrust); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 20, 239); +#else + mavlink_roll_pitch_yaw_thrust_setpoint_t packet; + packet.time_boot_ms = time_boot_ms; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 20, 239); +#endif +} + +#endif + +// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING + + +/** + * @brief Get field time_boot_ms from roll_pitch_yaw_thrust_setpoint message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field roll from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired roll angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired pitch angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message + * + * @return Desired yaw angle in radians + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct + * + * @param msg The message to decode + * @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + roll_pitch_yaw_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(msg); + roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg); + roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg); + roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg); + roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg); +#else + memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h new file mode 100644 index 0000000000..fee7734d01 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_allowed_area.h @@ -0,0 +1,276 @@ +// MESSAGE SAFETY_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 + +typedef struct __mavlink_safety_allowed_area_t +{ + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. +} mavlink_safety_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 +#define MAVLINK_MSG_ID_55_LEN 25 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ + "SAFETY_ALLOWED_AREA", \ + 7, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 25); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + return mavlink_finalize_message(msg, system_id, component_id, 25, 3); +} + +/** + * @brief Pack a safety_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 25); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 25); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 3); +} + +/** + * @brief Encode a safety_allowed_area struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) +{ + return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); +} + +/** + * @brief Send a safety_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[25]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25, 3); +#else + mavlink_safety_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.frame = frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25, 3); +#endif +} + +#endif + +// MESSAGE SAFETY_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field frame from safety_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field p1x from safety_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); + safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); + safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); + safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); + safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); + safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); + safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); +#else + memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h new file mode 100644 index 0000000000..35d9b3b254 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_safety_set_allowed_area.h @@ -0,0 +1,320 @@ +// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 + +typedef struct __mavlink_safety_set_allowed_area_t +{ + float p1x; ///< x position 1 / Latitude 1 + float p1y; ///< y position 1 / Longitude 1 + float p1z; ///< z position 1 / Altitude 1 + float p2x; ///< x position 2 / Latitude 2 + float p2y; ///< y position 2 / Longitude 2 + float p2z; ///< z position 2 / Altitude 2 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. +} mavlink_safety_set_allowed_area_t; + +#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 +#define MAVLINK_MSG_ID_54_LEN 27 + + + +#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ + "SAFETY_SET_ALLOWED_AREA", \ + 9, \ + { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ + { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ + { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ + { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ + { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ + { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ + } \ +} + + +/** + * @brief Pack a safety_set_allowed_area message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 27); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 27); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + return mavlink_finalize_message(msg, system_id, component_id, 27, 15); +} + +/** + * @brief Pack a safety_set_allowed_area message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 27); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 27); +#endif + + msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 27, 15); +} + +/** + * @brief Encode a safety_set_allowed_area struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param safety_set_allowed_area C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ + return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); +} + +/** + * @brief Send a safety_set_allowed_area message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + * @param p1x x position 1 / Latitude 1 + * @param p1y y position 1 / Longitude 1 + * @param p1z z position 1 / Altitude 1 + * @param p2x x position 2 / Latitude 2 + * @param p2y y position 2 / Longitude 2 + * @param p2z z position 2 / Altitude 2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[27]; + _mav_put_float(buf, 0, p1x); + _mav_put_float(buf, 4, p1y); + _mav_put_float(buf, 8, p1z); + _mav_put_float(buf, 12, p2x); + _mav_put_float(buf, 16, p2y); + _mav_put_float(buf, 20, p2z); + _mav_put_uint8_t(buf, 24, target_system); + _mav_put_uint8_t(buf, 25, target_component); + _mav_put_uint8_t(buf, 26, frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, 27, 15); +#else + mavlink_safety_set_allowed_area_t packet; + packet.p1x = p1x; + packet.p1y = p1y; + packet.p1z = p1z; + packet.p2x = p2x; + packet.p2y = p2y; + packet.p2z = p2z; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, 27, 15); +#endif +} + +#endif + +// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING + + +/** + * @brief Get field target_system from safety_set_allowed_area message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 24); +} + +/** + * @brief Get field target_component from safety_set_allowed_area message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 25); +} + +/** + * @brief Get field frame from safety_set_allowed_area message + * + * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + */ +static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field p1x from safety_set_allowed_area message + * + * @return x position 1 / Latitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field p1y from safety_set_allowed_area message + * + * @return y position 1 / Longitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field p1z from safety_set_allowed_area message + * + * @return z position 1 / Altitude 1 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2x from safety_set_allowed_area message + * + * @return x position 2 / Latitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p2y from safety_set_allowed_area message + * + * @return y position 2 / Longitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p2z from safety_set_allowed_area message + * + * @return z position 2 / Altitude 2 + */ +static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a safety_set_allowed_area message into a struct + * + * @param msg The message to decode + * @param safety_set_allowed_area C-struct to decode the message contents into + */ +static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) +{ +#if MAVLINK_NEED_BYTE_SWAP + safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); + safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); + safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); + safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); + safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); + safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); + safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); + safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); + safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); +#else + memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), 27); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h new file mode 100644 index 0000000000..145d959ade --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_imu.h @@ -0,0 +1,342 @@ +// MESSAGE SCALED_IMU PACKING + +#define MAVLINK_MSG_ID_SCALED_IMU 26 + +typedef struct __mavlink_scaled_imu_t +{ + uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) + int16_t xacc; ///< X acceleration (mg) + int16_t yacc; ///< Y acceleration (mg) + int16_t zacc; ///< Z acceleration (mg) + int16_t xgyro; ///< Angular speed around X axis (millirad /sec) + int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) + int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) + int16_t xmag; ///< X Magnetic field (milli tesla) + int16_t ymag; ///< Y Magnetic field (milli tesla) + int16_t zmag; ///< Z Magnetic field (milli tesla) +} mavlink_scaled_imu_t; + +#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 +#define MAVLINK_MSG_ID_26_LEN 22 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ + "SCALED_IMU", \ + 10, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ + { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ + { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ + { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ + { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ + { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ + { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ + { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ + { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ + { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ + } \ +} + + +/** + * @brief Pack a scaled_imu message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + return mavlink_finalize_message(msg, system_id, component_id, 22, 170); +} + +/** + * @brief Pack a scaled_imu message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + memcpy(_MAV_PAYLOAD(msg), buf, 22); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + memcpy(_MAV_PAYLOAD(msg), &packet, 22); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 170); +} + +/** + * @brief Encode a scaled_imu struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_imu C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) +{ + return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); +} + +/** + * @brief Send a scaled_imu message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (milliseconds since system boot) + * @param xacc X acceleration (mg) + * @param yacc Y acceleration (mg) + * @param zacc Z acceleration (mg) + * @param xgyro Angular speed around X axis (millirad /sec) + * @param ygyro Angular speed around Y axis (millirad /sec) + * @param zgyro Angular speed around Z axis (millirad /sec) + * @param xmag X Magnetic field (milli tesla) + * @param ymag Y Magnetic field (milli tesla) + * @param zmag Z Magnetic field (milli tesla) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[22]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int16_t(buf, 4, xacc); + _mav_put_int16_t(buf, 6, yacc); + _mav_put_int16_t(buf, 8, zacc); + _mav_put_int16_t(buf, 10, xgyro); + _mav_put_int16_t(buf, 12, ygyro); + _mav_put_int16_t(buf, 14, zgyro); + _mav_put_int16_t(buf, 16, xmag); + _mav_put_int16_t(buf, 18, ymag); + _mav_put_int16_t(buf, 20, zmag); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 22, 170); +#else + mavlink_scaled_imu_t packet; + packet.time_boot_ms = time_boot_ms; + packet.xacc = xacc; + packet.yacc = yacc; + packet.zacc = zacc; + packet.xgyro = xgyro; + packet.ygyro = ygyro; + packet.zgyro = zgyro; + packet.xmag = xmag; + packet.ymag = ymag; + packet.zmag = zmag; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 22, 170); +#endif +} + +#endif + +// MESSAGE SCALED_IMU UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_imu message + * + * @return Timestamp (milliseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field xacc from scaled_imu message + * + * @return X acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 4); +} + +/** + * @brief Get field yacc from scaled_imu message + * + * @return Y acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 6); +} + +/** + * @brief Get field zacc from scaled_imu message + * + * @return Z acceleration (mg) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 8); +} + +/** + * @brief Get field xgyro from scaled_imu message + * + * @return Angular speed around X axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 10); +} + +/** + * @brief Get field ygyro from scaled_imu message + * + * @return Angular speed around Y axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field zgyro from scaled_imu message + * + * @return Angular speed around Z axis (millirad /sec) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field xmag from scaled_imu message + * + * @return X Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field ymag from scaled_imu message + * + * @return Y Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 18); +} + +/** + * @brief Get field zmag from scaled_imu message + * + * @return Z Magnetic field (milli tesla) + */ +static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 20); +} + +/** + * @brief Decode a scaled_imu message into a struct + * + * @param msg The message to decode + * @param scaled_imu C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); + scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); + scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); + scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); + scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); + scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); + scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); + scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); + scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); + scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); +#else + memcpy(scaled_imu, _MAV_PAYLOAD(msg), 22); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h new file mode 100644 index 0000000000..428a7af223 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_scaled_pressure.h @@ -0,0 +1,210 @@ +// MESSAGE SCALED_PRESSURE PACKING + +#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 + +typedef struct __mavlink_scaled_pressure_t +{ + uint32_t time_boot_ms; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) + float press_abs; ///< Absolute pressure (hectopascal) + float press_diff; ///< Differential pressure 1 (hectopascal) + int16_t temperature; ///< Temperature measurement (0.01 degrees celsius) +} mavlink_scaled_pressure_t; + +#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 +#define MAVLINK_MSG_ID_29_LEN 14 + + + +#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ + "SCALED_PRESSURE", \ + 4, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ + { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ + { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ + { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ + } \ +} + + +/** + * @brief Pack a scaled_pressure message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + return mavlink_finalize_message(msg, system_id, component_id, 14, 115); +} + +/** + * @brief Pack a scaled_pressure message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + memcpy(_MAV_PAYLOAD(msg), buf, 14); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD(msg), &packet, 14); +#endif + + msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 115); +} + +/** + * @brief Encode a scaled_pressure struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param scaled_pressure C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) +{ + return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); +} + +/** + * @brief Send a scaled_pressure message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot) + * @param press_abs Absolute pressure (hectopascal) + * @param press_diff Differential pressure 1 (hectopascal) + * @param temperature Temperature measurement (0.01 degrees celsius) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[14]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, press_abs); + _mav_put_float(buf, 8, press_diff); + _mav_put_int16_t(buf, 12, temperature); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 14, 115); +#else + mavlink_scaled_pressure_t packet; + packet.time_boot_ms = time_boot_ms; + packet.press_abs = press_abs; + packet.press_diff = press_diff; + packet.temperature = temperature; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 14, 115); +#endif +} + +#endif + +// MESSAGE SCALED_PRESSURE UNPACKING + + +/** + * @brief Get field time_boot_ms from scaled_pressure message + * + * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) + */ +static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field press_abs from scaled_pressure message + * + * @return Absolute pressure (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field press_diff from scaled_pressure message + * + * @return Differential pressure 1 (hectopascal) + */ +static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field temperature from scaled_pressure message + * + * @return Temperature measurement (0.01 degrees celsius) + */ +static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a scaled_pressure message into a struct + * + * @param msg The message to decode + * @param scaled_pressure C-struct to decode the message contents into + */ +static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) +{ +#if MAVLINK_NEED_BYTE_SWAP + scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); + scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); + scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); + scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); +#else + memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 14); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h new file mode 100644 index 0000000000..2608edfa56 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_servo_output_raw.h @@ -0,0 +1,342 @@ +// MESSAGE SERVO_OUTPUT_RAW PACKING + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 37 + +typedef struct __mavlink_servo_output_raw_t +{ + uint32_t time_usec; ///< Timestamp (since UNIX epoch or microseconds since system boot) + uint16_t servo1_raw; ///< Servo output 1 value, in microseconds + uint16_t servo2_raw; ///< Servo output 2 value, in microseconds + uint16_t servo3_raw; ///< Servo output 3 value, in microseconds + uint16_t servo4_raw; ///< Servo output 4 value, in microseconds + uint16_t servo5_raw; ///< Servo output 5 value, in microseconds + uint16_t servo6_raw; ///< Servo output 6 value, in microseconds + uint16_t servo7_raw; ///< Servo output 7 value, in microseconds + uint16_t servo8_raw; ///< Servo output 8 value, in microseconds + uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. +} mavlink_servo_output_raw_t; + +#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 +#define MAVLINK_MSG_ID_37_LEN 21 + + + +#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ + "SERVO_OUTPUT_RAW", \ + 10, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ + { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ + { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ + { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ + { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ + { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ + { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ + { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ + { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ + { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ + } \ +} + + +/** + * @brief Pack a servo_output_raw message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD(msg), buf, 21); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + return mavlink_finalize_message(msg, system_id, component_id, 21, 222); +} + +/** + * @brief Pack a servo_output_raw message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + memcpy(_MAV_PAYLOAD(msg), buf, 21); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + memcpy(_MAV_PAYLOAD(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 222); +} + +/** + * @brief Encode a servo_output_raw struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param servo_output_raw C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) +{ + return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); +} + +/** + * @brief Send a servo_output_raw message + * @param chan MAVLink channel to send the message + * + * @param time_usec Timestamp (since UNIX epoch or microseconds since system boot) + * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + * @param servo1_raw Servo output 1 value, in microseconds + * @param servo2_raw Servo output 2 value, in microseconds + * @param servo3_raw Servo output 3 value, in microseconds + * @param servo4_raw Servo output 4 value, in microseconds + * @param servo5_raw Servo output 5 value, in microseconds + * @param servo6_raw Servo output 6 value, in microseconds + * @param servo7_raw Servo output 7 value, in microseconds + * @param servo8_raw Servo output 8 value, in microseconds + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_uint32_t(buf, 0, time_usec); + _mav_put_uint16_t(buf, 4, servo1_raw); + _mav_put_uint16_t(buf, 6, servo2_raw); + _mav_put_uint16_t(buf, 8, servo3_raw); + _mav_put_uint16_t(buf, 10, servo4_raw); + _mav_put_uint16_t(buf, 12, servo5_raw); + _mav_put_uint16_t(buf, 14, servo6_raw); + _mav_put_uint16_t(buf, 16, servo7_raw); + _mav_put_uint16_t(buf, 18, servo8_raw); + _mav_put_uint8_t(buf, 20, port); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 222); +#else + mavlink_servo_output_raw_t packet; + packet.time_usec = time_usec; + packet.servo1_raw = servo1_raw; + packet.servo2_raw = servo2_raw; + packet.servo3_raw = servo3_raw; + packet.servo4_raw = servo4_raw; + packet.servo5_raw = servo5_raw; + packet.servo6_raw = servo6_raw; + packet.servo7_raw = servo7_raw; + packet.servo8_raw = servo8_raw; + packet.port = port; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 222); +#endif +} + +#endif + +// MESSAGE SERVO_OUTPUT_RAW UNPACKING + + +/** + * @brief Get field time_usec from servo_output_raw message + * + * @return Timestamp (since UNIX epoch or microseconds since system boot) + */ +static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field port from servo_output_raw message + * + * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + */ +static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field servo1_raw from servo_output_raw message + * + * @return Servo output 1 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field servo2_raw from servo_output_raw message + * + * @return Servo output 2 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field servo3_raw from servo_output_raw message + * + * @return Servo output 3 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field servo4_raw from servo_output_raw message + * + * @return Servo output 4 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field servo5_raw from servo_output_raw message + * + * @return Servo output 5 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field servo6_raw from servo_output_raw message + * + * @return Servo output 6 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field servo7_raw from servo_output_raw message + * + * @return Servo output 7 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field servo8_raw from servo_output_raw message + * + * @return Servo output 8 value, in microseconds + */ +static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Decode a servo_output_raw message into a struct + * + * @param msg The message to decode + * @param servo_output_raw C-struct to decode the message contents into + */ +static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) +{ +#if MAVLINK_NEED_BYTE_SWAP + servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); + servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); + servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); + servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); + servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); + servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); + servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); + servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); + servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); + servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); +#else + memcpy(servo_output_raw, _MAV_PAYLOAD(msg), 21); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_flight_mode.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_flight_mode.h new file mode 100644 index 0000000000..b04abd6e84 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_flight_mode.h @@ -0,0 +1,166 @@ +// MESSAGE SET_FLIGHT_MODE PACKING + +#define MAVLINK_MSG_ID_SET_FLIGHT_MODE 12 + +typedef struct __mavlink_set_flight_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t flight_mode; ///< The new navigation mode +} mavlink_set_flight_mode_t; + +#define MAVLINK_MSG_ID_SET_FLIGHT_MODE_LEN 2 +#define MAVLINK_MSG_ID_12_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_SET_FLIGHT_MODE { \ + "SET_FLIGHT_MODE", \ + 2, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_flight_mode_t, target) }, \ + { "flight_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_flight_mode_t, flight_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_flight_mode message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system setting the mode + * @param flight_mode The new navigation mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_flight_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, uint8_t flight_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, flight_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_set_flight_mode_t packet; + packet.target = target; + packet.flight_mode = flight_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_FLIGHT_MODE; + return mavlink_finalize_message(msg, system_id, component_id, 2, 194); +} + +/** + * @brief Pack a set_flight_mode message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the mode + * @param flight_mode The new navigation mode + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_flight_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,uint8_t flight_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, flight_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_set_flight_mode_t packet; + packet.target = target; + packet.flight_mode = flight_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_FLIGHT_MODE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 194); +} + +/** + * @brief Encode a set_flight_mode struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_flight_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_flight_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_flight_mode_t* set_flight_mode) +{ + return mavlink_msg_set_flight_mode_pack(system_id, component_id, msg, set_flight_mode->target, set_flight_mode->flight_mode); +} + +/** + * @brief Send a set_flight_mode message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the mode + * @param flight_mode The new navigation mode + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_flight_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t flight_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, flight_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_FLIGHT_MODE, buf, 2, 194); +#else + mavlink_set_flight_mode_t packet; + packet.target = target; + packet.flight_mode = flight_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_FLIGHT_MODE, (const char *)&packet, 2, 194); +#endif +} + +#endif + +// MESSAGE SET_FLIGHT_MODE UNPACKING + + +/** + * @brief Get field target from set_flight_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_flight_mode_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field flight_mode from set_flight_mode message + * + * @return The new navigation mode + */ +static inline uint8_t mavlink_msg_set_flight_mode_get_flight_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a set_flight_mode message into a struct + * + * @param msg The message to decode + * @param set_flight_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_flight_mode_decode(const mavlink_message_t* msg, mavlink_set_flight_mode_t* set_flight_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_flight_mode->target = mavlink_msg_set_flight_mode_get_target(msg); + set_flight_mode->flight_mode = mavlink_msg_set_flight_mode_get_flight_mode(msg); +#else + memcpy(set_flight_mode, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h new file mode 100644 index 0000000000..ea34731c9e --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_global_position_setpoint_int.h @@ -0,0 +1,232 @@ +// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT PACKING + +#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53 + +typedef struct __mavlink_set_global_position_setpoint_int_t +{ + int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7 + int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7 + int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up) + int16_t yaw; ///< Desired yaw angle in degrees * 100 + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT +} mavlink_set_global_position_setpoint_int_t; + +#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 +#define MAVLINK_MSG_ID_53_LEN 15 + + + +#define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \ + "SET_GLOBAL_POSITION_SETPOINT_INT", \ + 5, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_global_position_setpoint_int_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_global_position_setpoint_int_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_global_position_setpoint_int_t, altitude) }, \ + { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_set_global_position_setpoint_int_t, yaw) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_global_position_setpoint_int_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_global_position_setpoint_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 15); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message(msg, system_id, component_id, 15, 33); +} + +/** + * @brief Pack a set_global_position_setpoint_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 15); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 15); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 33); +} + +/** + * @brief Encode a set_global_position_setpoint_int struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_global_position_setpoint_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) +{ + return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw); +} + +/** + * @brief Send a set_global_position_setpoint_int message + * @param chan MAVLink channel to send the message + * + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + * @param latitude WGS84 Latitude position in degrees * 1E7 + * @param longitude WGS84 Longitude position in degrees * 1E7 + * @param altitude WGS84 Altitude in meters * 1000 (positive for up) + * @param yaw Desired yaw angle in degrees * 100 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[15]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_int16_t(buf, 12, yaw); + _mav_put_uint8_t(buf, 14, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 33); +#else + mavlink_set_global_position_setpoint_int_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.yaw = yaw; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 33); +#endif +} + +#endif + +// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING + + +/** + * @brief Get field coordinate_frame from set_global_position_setpoint_int message + * + * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + */ +static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field latitude from set_global_position_setpoint_int message + * + * @return WGS84 Latitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_global_position_setpoint_int message + * + * @return WGS84 Longitude position in degrees * 1E7 + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_global_position_setpoint_int message + * + * @return WGS84 Altitude in meters * 1000 (positive for up) + */ +static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field yaw from set_global_position_setpoint_int message + * + * @return Desired yaw angle in degrees * 100 + */ +static inline int16_t mavlink_msg_set_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Decode a set_global_position_setpoint_int message into a struct + * + * @param msg The message to decode + * @param set_global_position_setpoint_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_global_position_setpoint_int->latitude = mavlink_msg_set_global_position_setpoint_int_get_latitude(msg); + set_global_position_setpoint_int->longitude = mavlink_msg_set_global_position_setpoint_int_get_longitude(msg); + set_global_position_setpoint_int->altitude = mavlink_msg_set_global_position_setpoint_int_get_altitude(msg); + set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg); + set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg); +#else + memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), 15); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h new file mode 100644 index 0000000000..ee6f18af56 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_gps_global_origin.h @@ -0,0 +1,210 @@ +// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 + +typedef struct __mavlink_set_gps_global_origin_t +{ + int32_t latitude; ///< global position * 1E7 + int32_t longitude; ///< global position * 1E7 + int32_t altitude; ///< global position * 1000 + uint8_t target_system; ///< System ID +} mavlink_set_gps_global_origin_t; + +#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 +#define MAVLINK_MSG_ID_48_LEN 13 + + + +#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ + "SET_GPS_GLOBAL_ORIGIN", \ + 4, \ + { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ + { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ + { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ + } \ +} + + +/** + * @brief Pack a set_gps_global_origin message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD(msg), buf, 13); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message(msg, system_id, component_id, 13, 41); +} + +/** + * @brief Pack a set_gps_global_origin message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + memcpy(_MAV_PAYLOAD(msg), buf, 13); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + memcpy(_MAV_PAYLOAD(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 41); +} + +/** + * @brief Encode a set_gps_global_origin struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_gps_global_origin C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ + return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); +} + +/** + * @brief Send a set_gps_global_origin message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param latitude global position * 1E7 + * @param longitude global position * 1E7 + * @param altitude global position * 1000 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_int32_t(buf, 0, latitude); + _mav_put_int32_t(buf, 4, longitude); + _mav_put_int32_t(buf, 8, altitude); + _mav_put_uint8_t(buf, 12, target_system); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, 13, 41); +#else + mavlink_set_gps_global_origin_t packet; + packet.latitude = latitude; + packet.longitude = longitude; + packet.altitude = altitude; + packet.target_system = target_system; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, 13, 41); +#endif +} + +#endif + +// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING + + +/** + * @brief Get field target_system from set_gps_global_origin message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field latitude from set_gps_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field longitude from set_gps_global_origin message + * + * @return global position * 1E7 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field altitude from set_gps_global_origin message + * + * @return global position * 1000 + */ +static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Decode a set_gps_global_origin message into a struct + * + * @param msg The message to decode + * @param set_gps_global_origin C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); + set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); + set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); + set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); +#else + memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), 13); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h new file mode 100644 index 0000000000..4024c9ef13 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_local_position_setpoint.h @@ -0,0 +1,276 @@ +// MESSAGE SET_LOCAL_POSITION_SETPOINT PACKING + +#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50 + +typedef struct __mavlink_set_local_position_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< Desired yaw angle + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU +} mavlink_set_local_position_setpoint_t; + +#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 +#define MAVLINK_MSG_ID_50_LEN 19 + + + +#define MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT { \ + "SET_LOCAL_POSITION_SETPOINT", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_local_position_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_local_position_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_local_position_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_local_position_setpoint_t, yaw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_local_position_setpoint_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_local_position_setpoint_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_set_local_position_setpoint_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a set_local_position_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 19); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 19); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 19, 214); +} + +/** + * @brief Pack a set_local_position_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + memcpy(_MAV_PAYLOAD(msg), buf, 19); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD(msg), &packet, 19); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 19, 214); +} + +/** + * @brief Encode a set_local_position_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_local_position_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint) +{ + return mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw); +} + +/** + * @brief Send a set_local_position_setpoint message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + * @param x x position + * @param y y position + * @param z z position + * @param yaw Desired yaw angle + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[19]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + _mav_put_uint8_t(buf, 18, coordinate_frame); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, 19, 214); +#else + mavlink_set_local_position_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, 19, 214); +#endif +} + +#endif + +// MESSAGE SET_LOCAL_POSITION_SETPOINT UNPACKING + + +/** + * @brief Get field target_system from set_local_position_setpoint message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_local_position_setpoint message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field coordinate_frame from set_local_position_setpoint message + * + * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + */ +static inline uint8_t mavlink_msg_set_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field x from set_local_position_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from set_local_position_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from set_local_position_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_set_local_position_setpoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from set_local_position_setpoint message + * + * @return Desired yaw angle + */ +static inline float mavlink_msg_set_local_position_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_local_position_setpoint message into a struct + * + * @param msg The message to decode + * @param set_local_position_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_set_local_position_setpoint_t* set_local_position_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_local_position_setpoint->x = mavlink_msg_set_local_position_setpoint_get_x(msg); + set_local_position_setpoint->y = mavlink_msg_set_local_position_setpoint_get_y(msg); + set_local_position_setpoint->z = mavlink_msg_set_local_position_setpoint_get_z(msg); + set_local_position_setpoint->yaw = mavlink_msg_set_local_position_setpoint_get_yaw(msg); + set_local_position_setpoint->target_system = mavlink_msg_set_local_position_setpoint_get_target_system(msg); + set_local_position_setpoint->target_component = mavlink_msg_set_local_position_setpoint_get_target_component(msg); + set_local_position_setpoint->coordinate_frame = mavlink_msg_set_local_position_setpoint_get_coordinate_frame(msg); +#else + memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), 19); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h new file mode 100644 index 0000000000..b622de0ea9 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_mode.h @@ -0,0 +1,188 @@ +// MESSAGE SET_MODE PACKING + +#define MAVLINK_MSG_ID_SET_MODE 11 + +typedef struct __mavlink_set_mode_t +{ + uint32_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot. + uint8_t target_system; ///< The system setting the mode + uint8_t base_mode; ///< The new base mode +} mavlink_set_mode_t; + +#define MAVLINK_MSG_ID_SET_MODE_LEN 6 +#define MAVLINK_MSG_ID_11_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_SET_MODE { \ + "SET_MODE", \ + 3, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_mode message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + return mavlink_finalize_message(msg, system_id, component_id, 6, 89); +} + +/** + * @brief Pack a set_mode message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_MODE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 89); +} + +/** + * @brief Encode a set_mode struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) +{ + return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); +} + +/** + * @brief Send a set_mode message + * @param chan MAVLink channel to send the message + * + * @param target_system The system setting the mode + * @param base_mode The new base mode + * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, target_system); + _mav_put_uint8_t(buf, 5, base_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 6, 89); +#else + mavlink_set_mode_t packet; + packet.custom_mode = custom_mode; + packet.target_system = target_system; + packet.base_mode = base_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 6, 89); +#endif +} + +#endif + +// MESSAGE SET_MODE UNPACKING + + +/** + * @brief Get field target_system from set_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field base_mode from set_mode message + * + * @return The new base mode + */ +static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field custom_mode from set_mode message + * + * @return The new autopilot-specific mode. This field can be ignored by an autopilot. + */ +static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Decode a set_mode message into a struct + * + * @param msg The message to decode + * @param set_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); + set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); + set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); +#else + memcpy(set_mode, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h new file mode 100644 index 0000000000..0141f77520 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h @@ -0,0 +1,254 @@ +// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57 + +typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t +{ + float roll_speed; ///< Desired roll angular speed in rad/s + float pitch_speed; ///< Desired pitch angular speed in rad/s + float yaw_speed; ///< Desired yaw angular speed in rad/s + float thrust; ///< Collective thrust, normalized to 0 .. 1 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_roll_pitch_yaw_speed_thrust_t; + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 +#define MAVLINK_MSG_ID_57_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \ + "SET_ROLL_PITCH_YAW_SPEED_THRUST", \ + 6, \ + { { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \ + { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \ + { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_roll_pitch_yaw_speed_thrust message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; + return mavlink_finalize_message(msg, system_id, component_id, 18, 24); +} + +/** + * @brief Pack a set_roll_pitch_yaw_speed_thrust message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float roll_speed,float pitch_speed,float yaw_speed,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 24); +} + +/** + * @brief Encode a set_roll_pitch_yaw_speed_thrust struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) +{ + return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust); +} + +/** + * @brief Send a set_roll_pitch_yaw_speed_thrust message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll_speed Desired roll angular speed in rad/s + * @param pitch_speed Desired pitch angular speed in rad/s + * @param yaw_speed Desired yaw angular speed in rad/s + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll_speed); + _mav_put_float(buf, 4, pitch_speed); + _mav_put_float(buf, 8, yaw_speed); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, 18, 24); +#else + mavlink_set_roll_pitch_yaw_speed_thrust_t packet; + packet.roll_speed = roll_speed; + packet.pitch_speed = pitch_speed; + packet.yaw_speed = yaw_speed; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, 18, 24); +#endif +} + +#endif + +// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING + + +/** + * @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired roll angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired pitch angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message + * + * @return Desired yaw angular speed in rad/s + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg); + set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg); + set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg); + set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg); + set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg); + set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg); +#else + memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h new file mode 100644 index 0000000000..453cf7b9c8 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h @@ -0,0 +1,254 @@ +// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56 + +typedef struct __mavlink_set_roll_pitch_yaw_thrust_t +{ + float roll; ///< Desired roll angle in radians + float pitch; ///< Desired pitch angle in radians + float yaw; ///< Desired yaw angle in radians + float thrust; ///< Collective thrust, normalized to 0 .. 1 + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_set_roll_pitch_yaw_thrust_t; + +#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 +#define MAVLINK_MSG_ID_56_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \ + "SET_ROLL_PITCH_YAW_THRUST", \ + 6, \ + { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a set_roll_pitch_yaw_thrust message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message(msg, system_id, component_id, 18, 100); +} + +/** + * @brief Pack a set_roll_pitch_yaw_thrust message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float roll,float pitch,float yaw,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 100); +} + +/** + * @brief Encode a set_roll_pitch_yaw_thrust struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_roll_pitch_yaw_thrust C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) +{ + return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust); +} + +/** + * @brief Send a set_roll_pitch_yaw_thrust message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param roll Desired roll angle in radians + * @param pitch Desired pitch angle in radians + * @param yaw Desired yaw angle in radians + * @param thrust Collective thrust, normalized to 0 .. 1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, 18, 100); +#else + mavlink_set_roll_pitch_yaw_thrust_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 18, 100); +#endif +} + +#endif + +// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING + + +/** + * @brief Get field target_system from set_roll_pitch_yaw_thrust message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from set_roll_pitch_yaw_thrust message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field roll from set_roll_pitch_yaw_thrust message + * + * @return Desired roll angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from set_roll_pitch_yaw_thrust message + * + * @return Desired pitch angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from set_roll_pitch_yaw_thrust message + * + * @return Desired yaw angle in radians + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from set_roll_pitch_yaw_thrust message + * + * @return Collective thrust, normalized to 0 .. 1 + */ +static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a set_roll_pitch_yaw_thrust message into a struct + * + * @param msg The message to decode + * @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg); + set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg); + set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg); + set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg); + set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg); + set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg); +#else + memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_safety_mode.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_safety_mode.h new file mode 100644 index 0000000000..b12bf75f6d --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_set_safety_mode.h @@ -0,0 +1,166 @@ +// MESSAGE SET_SAFETY_MODE PACKING + +#define MAVLINK_MSG_ID_SET_SAFETY_MODE 13 + +typedef struct __mavlink_set_safety_mode_t +{ + uint8_t target; ///< The system setting the mode + uint8_t safety_mode; ///< The new safety mode. The MAV will reject some mode changes during flight. +} mavlink_set_safety_mode_t; + +#define MAVLINK_MSG_ID_SET_SAFETY_MODE_LEN 2 +#define MAVLINK_MSG_ID_13_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_SET_SAFETY_MODE { \ + "SET_SAFETY_MODE", \ + 2, \ + { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_safety_mode_t, target) }, \ + { "safety_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_safety_mode_t, safety_mode) }, \ + } \ +} + + +/** + * @brief Pack a set_safety_mode message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system setting the mode + * @param safety_mode The new safety mode. The MAV will reject some mode changes during flight. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_safety_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, uint8_t safety_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, safety_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_set_safety_mode_t packet; + packet.target = target; + packet.safety_mode = safety_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_SAFETY_MODE; + return mavlink_finalize_message(msg, system_id, component_id, 2, 8); +} + +/** + * @brief Pack a set_safety_mode message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the mode + * @param safety_mode The new safety mode. The MAV will reject some mode changes during flight. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_safety_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,uint8_t safety_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, safety_mode); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_set_safety_mode_t packet; + packet.target = target; + packet.safety_mode = safety_mode; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_SAFETY_MODE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 8); +} + +/** + * @brief Encode a set_safety_mode struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_safety_mode C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_safety_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_safety_mode_t* set_safety_mode) +{ + return mavlink_msg_set_safety_mode_pack(system_id, component_id, msg, set_safety_mode->target, set_safety_mode->safety_mode); +} + +/** + * @brief Send a set_safety_mode message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the mode + * @param safety_mode The new safety mode. The MAV will reject some mode changes during flight. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_safety_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t safety_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target); + _mav_put_uint8_t(buf, 1, safety_mode); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SAFETY_MODE, buf, 2, 8); +#else + mavlink_set_safety_mode_t packet; + packet.target = target; + packet.safety_mode = safety_mode; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_SAFETY_MODE, (const char *)&packet, 2, 8); +#endif +} + +#endif + +// MESSAGE SET_SAFETY_MODE UNPACKING + + +/** + * @brief Get field target from set_safety_mode message + * + * @return The system setting the mode + */ +static inline uint8_t mavlink_msg_set_safety_mode_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field safety_mode from set_safety_mode message + * + * @return The new safety mode. The MAV will reject some mode changes during flight. + */ +static inline uint8_t mavlink_msg_set_safety_mode_get_safety_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a set_safety_mode message into a struct + * + * @param msg The message to decode + * @param set_safety_mode C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_safety_mode_decode(const mavlink_message_t* msg, mavlink_set_safety_mode_t* set_safety_mode) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_safety_mode->target = mavlink_msg_set_safety_mode_get_target(msg); + set_safety_mode->safety_mode = mavlink_msg_set_safety_mode_get_safety_mode(msg); +#else + memcpy(set_safety_mode, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h new file mode 100644 index 0000000000..7dea690d29 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_state_correction.h @@ -0,0 +1,320 @@ +// MESSAGE STATE_CORRECTION PACKING + +#define MAVLINK_MSG_ID_STATE_CORRECTION 64 + +typedef struct __mavlink_state_correction_t +{ + float xErr; ///< x position error + float yErr; ///< y position error + float zErr; ///< z position error + float rollErr; ///< roll error (radians) + float pitchErr; ///< pitch error (radians) + float yawErr; ///< yaw error (radians) + float vxErr; ///< x velocity + float vyErr; ///< y velocity + float vzErr; ///< z velocity +} mavlink_state_correction_t; + +#define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 +#define MAVLINK_MSG_ID_64_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \ + "STATE_CORRECTION", \ + 9, \ + { { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \ + { "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \ + { "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \ + { "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \ + { "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \ + { "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \ + { "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \ + { "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \ + { "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \ + } \ +} + + +/** + * @brief Pack a state_correction message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + return mavlink_finalize_message(msg, system_id, component_id, 36, 130); +} + +/** + * @brief Pack a state_correction message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 130); +} + +/** + * @brief Encode a state_correction struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param state_correction C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) +{ + return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); +} + +/** + * @brief Send a state_correction message + * @param chan MAVLink channel to send the message + * + * @param xErr x position error + * @param yErr y position error + * @param zErr z position error + * @param rollErr roll error (radians) + * @param pitchErr pitch error (radians) + * @param yawErr yaw error (radians) + * @param vxErr x velocity + * @param vyErr y velocity + * @param vzErr z velocity + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, xErr); + _mav_put_float(buf, 4, yErr); + _mav_put_float(buf, 8, zErr); + _mav_put_float(buf, 12, rollErr); + _mav_put_float(buf, 16, pitchErr); + _mav_put_float(buf, 20, yawErr); + _mav_put_float(buf, 24, vxErr); + _mav_put_float(buf, 28, vyErr); + _mav_put_float(buf, 32, vzErr); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, 36, 130); +#else + mavlink_state_correction_t packet; + packet.xErr = xErr; + packet.yErr = yErr; + packet.zErr = zErr; + packet.rollErr = rollErr; + packet.pitchErr = pitchErr; + packet.yawErr = yawErr; + packet.vxErr = vxErr; + packet.vyErr = vyErr; + packet.vzErr = vzErr; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, 36, 130); +#endif +} + +#endif + +// MESSAGE STATE_CORRECTION UNPACKING + + +/** + * @brief Get field xErr from state_correction message + * + * @return x position error + */ +static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field yErr from state_correction message + * + * @return y position error + */ +static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field zErr from state_correction message + * + * @return z position error + */ +static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field rollErr from state_correction message + * + * @return roll error (radians) + */ +static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pitchErr from state_correction message + * + * @return pitch error (radians) + */ +static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field yawErr from state_correction message + * + * @return yaw error (radians) + */ +static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vxErr from state_correction message + * + * @return x velocity + */ +static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field vyErr from state_correction message + * + * @return y velocity + */ +static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field vzErr from state_correction message + * + * @return z velocity + */ +static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a state_correction message into a struct + * + * @param msg The message to decode + * @param state_correction C-struct to decode the message contents into + */ +static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction) +{ +#if MAVLINK_NEED_BYTE_SWAP + state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg); + state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg); + state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg); + state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg); + state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg); + state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg); + state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg); + state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); + state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); +#else + memcpy(state_correction, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h new file mode 100644 index 0000000000..90271de8d1 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_statustext.h @@ -0,0 +1,160 @@ +// MESSAGE STATUSTEXT PACKING + +#define MAVLINK_MSG_ID_STATUSTEXT 253 + +typedef struct __mavlink_statustext_t +{ + uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault + char text[50]; ///< Status text message, without null termination character +} mavlink_statustext_t; + +#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 +#define MAVLINK_MSG_ID_253_LEN 51 + +#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 + +#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ + "STATUSTEXT", \ + 2, \ + { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ + { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ + } \ +} + + +/** + * @brief Pack a statustext message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD(msg), buf, 51); +#else + mavlink_statustext_t packet; + packet.severity = severity; + memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD(msg), &packet, 51); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + return mavlink_finalize_message(msg, system_id, component_id, 51, 83); +} + +/** + * @brief Pack a statustext message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t severity,const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + memcpy(_MAV_PAYLOAD(msg), buf, 51); +#else + mavlink_statustext_t packet; + packet.severity = severity; + memcpy(packet.text, text, sizeof(char)*50); + memcpy(_MAV_PAYLOAD(msg), &packet, 51); +#endif + + msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51, 83); +} + +/** + * @brief Encode a statustext struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param statustext C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) +{ + return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); +} + +/** + * @brief Send a statustext message + * @param chan MAVLink channel to send the message + * + * @param severity Severity of status, 0 = info message, 255 = critical fault + * @param text Status text message, without null termination character + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[51]; + _mav_put_uint8_t(buf, 0, severity); + _mav_put_char_array(buf, 1, text, 50); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51, 83); +#else + mavlink_statustext_t packet; + packet.severity = severity; + memcpy(packet.text, text, sizeof(char)*50); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51, 83); +#endif +} + +#endif + +// MESSAGE STATUSTEXT UNPACKING + + +/** + * @brief Get field severity from statustext message + * + * @return Severity of status, 0 = info message, 255 = critical fault + */ +static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field text from statustext message + * + * @return Status text message, without null termination character + */ +static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) +{ + return _MAV_RETURN_char_array(msg, text, 50, 1); +} + +/** + * @brief Decode a statustext message into a struct + * + * @param msg The message to decode + * @param statustext C-struct to decode the message contents into + */ +static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) +{ +#if MAVLINK_NEED_BYTE_SWAP + statustext->severity = mavlink_msg_statustext_get_severity(msg); + mavlink_msg_statustext_get_text(msg, statustext->text); +#else + memcpy(statustext, _MAV_PAYLOAD(msg), 51); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h new file mode 100644 index 0000000000..adada471d1 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_sys_status.h @@ -0,0 +1,408 @@ +// MESSAGE SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_SYS_STATUS 1 + +typedef struct __mavlink_sys_status_t +{ + uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + uint16_t voltage_battery; ///< Battery voltage, in millivolts (1 = 1 millivolt) + int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + uint16_t drop_rate_comm; ///< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + uint16_t errors_comm; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + uint16_t errors_count1; ///< Autopilot-specific errors + uint16_t errors_count2; ///< Autopilot-specific errors + uint16_t errors_count3; ///< Autopilot-specific errors + uint16_t errors_count4; ///< Autopilot-specific errors + int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery +} mavlink_sys_status_t; + +#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 +#define MAVLINK_MSG_ID_1_LEN 31 + + + +#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ + "SYS_STATUS", \ + 13, \ + { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ + { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ + { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ + { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ + { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ + { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ + { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ + { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ + { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ + { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ + { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ + { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ + { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ + } \ +} + + +/** + * @brief Pack a sys_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD(msg), buf, 31); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD(msg), &packet, 31); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 31, 124); +} + +/** + * @brief Pack a sys_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + memcpy(_MAV_PAYLOAD(msg), buf, 31); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + memcpy(_MAV_PAYLOAD(msg), &packet, 31); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 124); +} + +/** + * @brief Encode a sys_status struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) +{ + return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); +} + +/** + * @brief Send a sys_status message + * @param chan MAVLink channel to send the message + * + * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) + * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + * @param errors_count1 Autopilot-specific errors + * @param errors_count2 Autopilot-specific errors + * @param errors_count3 Autopilot-specific errors + * @param errors_count4 Autopilot-specific errors + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[31]; + _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); + _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); + _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); + _mav_put_uint16_t(buf, 12, load); + _mav_put_uint16_t(buf, 14, voltage_battery); + _mav_put_int16_t(buf, 16, current_battery); + _mav_put_uint16_t(buf, 18, drop_rate_comm); + _mav_put_uint16_t(buf, 20, errors_comm); + _mav_put_uint16_t(buf, 22, errors_count1); + _mav_put_uint16_t(buf, 24, errors_count2); + _mav_put_uint16_t(buf, 26, errors_count3); + _mav_put_uint16_t(buf, 28, errors_count4); + _mav_put_int8_t(buf, 30, battery_remaining); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 31, 124); +#else + mavlink_sys_status_t packet; + packet.onboard_control_sensors_present = onboard_control_sensors_present; + packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; + packet.onboard_control_sensors_health = onboard_control_sensors_health; + packet.load = load; + packet.voltage_battery = voltage_battery; + packet.current_battery = current_battery; + packet.drop_rate_comm = drop_rate_comm; + packet.errors_comm = errors_comm; + packet.errors_count1 = errors_count1; + packet.errors_count2 = errors_count2; + packet.errors_count3 = errors_count3; + packet.errors_count4 = errors_count4; + packet.battery_remaining = battery_remaining; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 31, 124); +#endif +} + +#endif + +// MESSAGE SYS_STATUS UNPACKING + + +/** + * @brief Get field onboard_control_sensors_present from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field onboard_control_sensors_enabled from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field onboard_control_sensors_health from sys_status message + * + * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + */ +static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field load from sys_status message + * + * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + */ +static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field voltage_battery from sys_status message + * + * @return Battery voltage, in millivolts (1 = 1 millivolt) + */ +static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 14); +} + +/** + * @brief Get field current_battery from sys_status message + * + * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + */ +static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field battery_remaining from sys_status message + * + * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + */ +static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 30); +} + +/** + * @brief Get field drop_rate_comm from sys_status message + * + * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field errors_comm from sys_status message + * + * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 20); +} + +/** + * @brief Get field errors_count1 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 22); +} + +/** + * @brief Get field errors_count2 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field errors_count3 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 26); +} + +/** + * @brief Get field errors_count4 from sys_status message + * + * @return Autopilot-specific errors + */ +static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Decode a sys_status message into a struct + * + * @param msg The message to decode + * @param sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); + sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); + sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); + sys_status->load = mavlink_msg_sys_status_get_load(msg); + sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); + sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); + sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); + sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); + sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); + sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); + sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); + sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); + sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); +#else + memcpy(sys_status, _MAV_PAYLOAD(msg), 31); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h new file mode 100644 index 0000000000..a46db49c31 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time.h @@ -0,0 +1,166 @@ +// MESSAGE SYSTEM_TIME PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME 2 + +typedef struct __mavlink_system_time_t +{ + uint64_t time_unix_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch. + uint32_t time_boot_ms; ///< Timestamp of the component clock since boot time in milliseconds. +} mavlink_system_time_t; + +#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 +#define MAVLINK_MSG_ID_2_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ + "SYSTEM_TIME", \ + 2, \ + { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ + { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ + } \ +} + + +/** + * @brief Pack a system_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + return mavlink_finalize_message(msg, system_id, component_id, 12, 137); +} + +/** + * @brief Pack a system_time message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_unix_usec,uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 137); +} + +/** + * @brief Encode a system_time struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param system_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) +{ + return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); +} + +/** + * @brief Send a system_time message + * @param chan MAVLink channel to send the message + * + * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. + * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_uint64_t(buf, 0, time_unix_usec); + _mav_put_uint32_t(buf, 8, time_boot_ms); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, 12, 137); +#else + mavlink_system_time_t packet; + packet.time_unix_usec = time_unix_usec; + packet.time_boot_ms = time_boot_ms; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, 12, 137); +#endif +} + +#endif + +// MESSAGE SYSTEM_TIME UNPACKING + + +/** + * @brief Get field time_unix_usec from system_time message + * + * @return Timestamp of the master clock in microseconds since UNIX epoch. + */ +static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field time_boot_ms from system_time message + * + * @return Timestamp of the component clock since boot time in milliseconds. + */ +static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Decode a system_time message into a struct + * + * @param msg The message to decode + * @param system_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) +{ +#if MAVLINK_NEED_BYTE_SWAP + system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); + system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); +#else + memcpy(system_time, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time_utc.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time_utc.h new file mode 100644 index 0000000000..fb0ed4e49c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_system_time_utc.h @@ -0,0 +1,166 @@ +// MESSAGE SYSTEM_TIME_UTC PACKING + +#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC 3 + +typedef struct __mavlink_system_time_utc_t +{ + uint32_t utc_date; ///< GPS UTC date ddmmyy + uint32_t utc_time; ///< GPS UTC time hhmmss +} mavlink_system_time_utc_t; + +#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC_LEN 8 +#define MAVLINK_MSG_ID_3_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC { \ + "SYSTEM_TIME_UTC", \ + 2, \ + { { "utc_date", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_system_time_utc_t, utc_date) }, \ + { "utc_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_system_time_utc_t, utc_time) }, \ + } \ +} + + +/** + * @brief Pack a system_time_utc message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t utc_date, uint32_t utc_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, utc_date); + _mav_put_uint32_t(buf, 4, utc_time); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_system_time_utc_t packet; + packet.utc_date = utc_date; + packet.utc_time = utc_time; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; + return mavlink_finalize_message(msg, system_id, component_id, 8, 191); +} + +/** + * @brief Pack a system_time_utc message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t utc_date,uint32_t utc_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, utc_date); + _mav_put_uint32_t(buf, 4, utc_time); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_system_time_utc_t packet; + packet.utc_date = utc_date; + packet.utc_time = utc_time; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 191); +} + +/** + * @brief Encode a system_time_utc struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param system_time_utc C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_system_time_utc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_utc_t* system_time_utc) +{ + return mavlink_msg_system_time_utc_pack(system_id, component_id, msg, system_time_utc->utc_date, system_time_utc->utc_time); +} + +/** + * @brief Send a system_time_utc message + * @param chan MAVLink channel to send the message + * + * @param utc_date GPS UTC date ddmmyy + * @param utc_time GPS UTC time hhmmss + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_system_time_utc_send(mavlink_channel_t chan, uint32_t utc_date, uint32_t utc_time) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, utc_date); + _mav_put_uint32_t(buf, 4, utc_time); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, buf, 8, 191); +#else + mavlink_system_time_utc_t packet; + packet.utc_date = utc_date; + packet.utc_time = utc_time; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, (const char *)&packet, 8, 191); +#endif +} + +#endif + +// MESSAGE SYSTEM_TIME_UTC UNPACKING + + +/** + * @brief Get field utc_date from system_time_utc message + * + * @return GPS UTC date ddmmyy + */ +static inline uint32_t mavlink_msg_system_time_utc_get_utc_date(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field utc_time from system_time_utc message + * + * @return GPS UTC time hhmmss + */ +static inline uint32_t mavlink_msg_system_time_utc_get_utc_time(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Decode a system_time_utc message into a struct + * + * @param msg The message to decode + * @param system_time_utc C-struct to decode the message contents into + */ +static inline void mavlink_msg_system_time_utc_decode(const mavlink_message_t* msg, mavlink_system_time_utc_t* system_time_utc) +{ +#if MAVLINK_NEED_BYTE_SWAP + system_time_utc->utc_date = mavlink_msg_system_time_utc_get_utc_date(msg); + system_time_utc->utc_time = mavlink_msg_system_time_utc_get_utc_time(msg); +#else + memcpy(system_time_utc, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h new file mode 100644 index 0000000000..3e4c09acdc --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vfr_hud.h @@ -0,0 +1,254 @@ +// MESSAGE VFR_HUD PACKING + +#define MAVLINK_MSG_ID_VFR_HUD 74 + +typedef struct __mavlink_vfr_hud_t +{ + float airspeed; ///< Current airspeed in m/s + float groundspeed; ///< Current ground speed in m/s + float alt; ///< Current altitude (MSL), in meters + float climb; ///< Current climb rate in meters/second + int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north) + uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100 +} mavlink_vfr_hud_t; + +#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 +#define MAVLINK_MSG_ID_74_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ + "VFR_HUD", \ + 6, \ + { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ + { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ + { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ + { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ + } \ +} + + +/** + * @brief Pack a vfr_hud message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + return mavlink_finalize_message(msg, system_id, component_id, 20, 20); +} + +/** + * @brief Pack a vfr_hud message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VFR_HUD; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 20); +} + +/** + * @brief Encode a vfr_hud struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vfr_hud C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) +{ + return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); +} + +/** + * @brief Send a vfr_hud message + * @param chan MAVLink channel to send the message + * + * @param airspeed Current airspeed in m/s + * @param groundspeed Current ground speed in m/s + * @param heading Current heading in degrees, in compass units (0..360, 0=north) + * @param throttle Current throttle setting in integer percent, 0 to 100 + * @param alt Current altitude (MSL), in meters + * @param climb Current climb rate in meters/second + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, airspeed); + _mav_put_float(buf, 4, groundspeed); + _mav_put_float(buf, 8, alt); + _mav_put_float(buf, 12, climb); + _mav_put_int16_t(buf, 16, heading); + _mav_put_uint16_t(buf, 18, throttle); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20, 20); +#else + mavlink_vfr_hud_t packet; + packet.airspeed = airspeed; + packet.groundspeed = groundspeed; + packet.alt = alt; + packet.climb = climb; + packet.heading = heading; + packet.throttle = throttle; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20, 20); +#endif +} + +#endif + +// MESSAGE VFR_HUD UNPACKING + + +/** + * @brief Get field airspeed from vfr_hud message + * + * @return Current airspeed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field groundspeed from vfr_hud message + * + * @return Current ground speed in m/s + */ +static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field heading from vfr_hud message + * + * @return Current heading in degrees, in compass units (0..360, 0=north) + */ +static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Get field throttle from vfr_hud message + * + * @return Current throttle setting in integer percent, 0 to 100 + */ +static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field alt from vfr_hud message + * + * @return Current altitude (MSL), in meters + */ +static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field climb from vfr_hud message + * + * @return Current climb rate in meters/second + */ +static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a vfr_hud message into a struct + * + * @param msg The message to decode + * @param vfr_hud C-struct to decode the message contents into + */ +static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) +{ +#if MAVLINK_NEED_BYTE_SWAP + vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); + vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); + vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); + vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); + vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); + vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); +#else + memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vicon_position_estimate.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000000..93db6edef9 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_vicon_position_estimate_t; + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_104_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ + "VICON_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vicon_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 56); +} + +/** + * @brief Pack a vicon_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 56); +} + +/** + * @brief Encode a vicon_position_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Send a vicon_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32, 56); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32, 56); +#endif +} + +#endif + +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vicon_position_estimate message into a struct + * + * @param msg The message to decode + * @param vicon_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +#else + memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_position_estimate.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000000..c99fc99ab1 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_102_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ + "VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 158); +} + +/** + * @brief Pack a vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 158); +} + +/** + * @brief Encode a vision_position_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Send a vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32, 158); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 158); +#endif +} + +#endif + +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +#else + memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_speed_estimate.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_speed_estimate.h new file mode 100644 index 0000000000..71d250c389 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_vision_speed_estimate.h @@ -0,0 +1,210 @@ +// MESSAGE VISION_SPEED_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 + +typedef struct __mavlink_vision_speed_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X speed + float y; ///< Global Y speed + float z; ///< Global Z speed +} mavlink_vision_speed_estimate_t; + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 +#define MAVLINK_MSG_ID_103_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ + "VISION_SPEED_ESTIMATE", \ + 4, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ + } \ +} + + +/** + * @brief Pack a vision_speed_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 20, 208); +} + +/** + * @brief Pack a vision_speed_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 208); +} + +/** + * @brief Encode a vision_speed_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Send a vision_speed_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20, 208); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20, 208); +#endif +} + +#endif + +// MESSAGE VISION_SPEED_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_speed_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_speed_estimate message + * + * @return Global X speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_speed_estimate message + * + * @return Global Y speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_speed_estimate message + * + * @return Global Z speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a vision_speed_estimate message into a struct + * + * @param msg The message to decode + * @param vision_speed_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); + vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); + vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); + vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); +#else + memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint.h new file mode 100644 index 0000000000..455607c44c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint.h @@ -0,0 +1,430 @@ +// MESSAGE WAYPOINT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT 39 + +typedef struct __mavlink_waypoint_t +{ + float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + float x; ///< PARAM5 / local: x position, global: latitude + float y; ///< PARAM6 / y position: global: longitude + float z; ///< PARAM7 / z position: global: altitude + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + uint8_t current; ///< false:0, true:1 + uint8_t autocontinue; ///< autocontinue to next wp +} mavlink_waypoint_t; + +#define MAVLINK_MSG_ID_WAYPOINT_LEN 36 +#define MAVLINK_MSG_ID_39_LEN 36 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT { \ + "WAYPOINT", \ + 14, \ + { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_waypoint_t, param1) }, \ + { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_waypoint_t, param2) }, \ + { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_waypoint_t, param3) }, \ + { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_waypoint_t, param4) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_waypoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_waypoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_waypoint_t, z) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_waypoint_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_waypoint_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_waypoint_t, target_component) }, \ + { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_waypoint_t, frame) }, \ + { "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_waypoint_t, command) }, \ + { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_waypoint_t, current) }, \ + { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_waypoint_t, autocontinue) }, \ + } \ +} + + +/** + * @brief Pack a waypoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_waypoint_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 36, 205); +} + +/** + * @brief Pack a waypoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint8_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + memcpy(_MAV_PAYLOAD(msg), buf, 36); +#else + mavlink_waypoint_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + memcpy(_MAV_PAYLOAD(msg), &packet, 36); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 205); +} + +/** + * @brief Encode a waypoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint) +{ + return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z); +} + +/** + * @brief Send a waypoint message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + * @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + * @param current false:0, true:1 + * @param autocontinue autocontinue to next wp + * @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + * @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + * @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + * @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + * @param x PARAM5 / local: x position, global: latitude + * @param y PARAM6 / y position: global: longitude + * @param z PARAM7 / z position: global: altitude + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[36]; + _mav_put_float(buf, 0, param1); + _mav_put_float(buf, 4, param2); + _mav_put_float(buf, 8, param3); + _mav_put_float(buf, 12, param4); + _mav_put_float(buf, 16, x); + _mav_put_float(buf, 20, y); + _mav_put_float(buf, 24, z); + _mav_put_uint16_t(buf, 28, seq); + _mav_put_uint8_t(buf, 30, target_system); + _mav_put_uint8_t(buf, 31, target_component); + _mav_put_uint8_t(buf, 32, frame); + _mav_put_uint8_t(buf, 33, command); + _mav_put_uint8_t(buf, 34, current); + _mav_put_uint8_t(buf, 35, autocontinue); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, buf, 36, 205); +#else + mavlink_waypoint_t packet; + packet.param1 = param1; + packet.param2 = param2; + packet.param3 = param3; + packet.param4 = param4; + packet.x = x; + packet.y = y; + packet.z = z; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + packet.frame = frame; + packet.command = command; + packet.current = current; + packet.autocontinue = autocontinue; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, (const char *)&packet, 36, 205); +#endif +} + +#endif + +// MESSAGE WAYPOINT UNPACKING + + +/** + * @brief Get field target_system from waypoint message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field target_component from waypoint message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field seq from waypoint message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field frame from waypoint message + * + * @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + */ +static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field command from waypoint message + * + * @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + */ +static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field current from waypoint message + * + * @return false:0, true:1 + */ +static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field autocontinue from waypoint message + * + * @return autocontinue to next wp + */ +static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 35); +} + +/** + * @brief Get field param1 from waypoint message + * + * @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + */ +static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field param2 from waypoint message + * + * @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + */ +static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field param3 from waypoint message + * + * @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + */ +static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field param4 from waypoint message + * + * @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + */ +static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field x from waypoint message + * + * @return PARAM5 / local: x position, global: latitude + */ +static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field y from waypoint message + * + * @return PARAM6 / y position: global: longitude + */ +static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field z from waypoint message + * + * @return PARAM7 / z position: global: altitude + */ +static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Decode a waypoint message into a struct + * + * @param msg The message to decode + * @param waypoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint->param1 = mavlink_msg_waypoint_get_param1(msg); + waypoint->param2 = mavlink_msg_waypoint_get_param2(msg); + waypoint->param3 = mavlink_msg_waypoint_get_param3(msg); + waypoint->param4 = mavlink_msg_waypoint_get_param4(msg); + waypoint->x = mavlink_msg_waypoint_get_x(msg); + waypoint->y = mavlink_msg_waypoint_get_y(msg); + waypoint->z = mavlink_msg_waypoint_get_z(msg); + waypoint->seq = mavlink_msg_waypoint_get_seq(msg); + waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg); + waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg); + waypoint->frame = mavlink_msg_waypoint_get_frame(msg); + waypoint->command = mavlink_msg_waypoint_get_command(msg); + waypoint->current = mavlink_msg_waypoint_get_current(msg); + waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg); +#else + memcpy(waypoint, _MAV_PAYLOAD(msg), 36); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_ack.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_ack.h new file mode 100644 index 0000000000..846ae88393 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_ack.h @@ -0,0 +1,188 @@ +// MESSAGE WAYPOINT_ACK PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_ACK 47 + +typedef struct __mavlink_waypoint_ack_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t type; ///< 0: OK, 1: Error +} mavlink_waypoint_ack_t; + +#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN 3 +#define MAVLINK_MSG_ID_47_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_ACK { \ + "WAYPOINT_ACK", \ + 3, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_ack_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_ack_t, target_component) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_ack_t, type) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_ack message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_waypoint_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; + return mavlink_finalize_message(msg, system_id, component_id, 3, 214); +} + +/** + * @brief Pack a waypoint_ack message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_waypoint_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 214); +} + +/** + * @brief Encode a waypoint_ack struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_ack C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack) +{ + return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type); +} + +/** + * @brief Send a waypoint_ack message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param type 0: OK, 1: Error + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + _mav_put_uint8_t(buf, 2, type); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_ACK, buf, 3, 214); +#else + mavlink_waypoint_ack_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + packet.type = type; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_ACK, (const char *)&packet, 3, 214); +#endif +} + +#endif + +// MESSAGE WAYPOINT_ACK UNPACKING + + +/** + * @brief Get field target_system from waypoint_ack message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from waypoint_ack message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field type from waypoint_ack message + * + * @return 0: OK, 1: Error + */ +static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a waypoint_ack message into a struct + * + * @param msg The message to decode + * @param waypoint_ack C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg); + waypoint_ack->target_component = mavlink_msg_waypoint_ack_get_target_component(msg); + waypoint_ack->type = mavlink_msg_waypoint_ack_get_type(msg); +#else + memcpy(waypoint_ack, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_clear_all.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_clear_all.h new file mode 100644 index 0000000000..4133b58d06 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_clear_all.h @@ -0,0 +1,166 @@ +// MESSAGE WAYPOINT_CLEAR_ALL PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45 + +typedef struct __mavlink_waypoint_clear_all_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_waypoint_clear_all_t; + +#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN 2 +#define MAVLINK_MSG_ID_45_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL { \ + "WAYPOINT_CLEAR_ALL", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_clear_all_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_clear_all_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_clear_all message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; + return mavlink_finalize_message(msg, system_id, component_id, 2, 229); +} + +/** + * @brief Pack a waypoint_clear_all message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 229); +} + +/** + * @brief Encode a waypoint_clear_all struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_clear_all C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ + return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component); +} + +/** + * @brief Send a waypoint_clear_all message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, buf, 2, 229); +#else + mavlink_waypoint_clear_all_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, (const char *)&packet, 2, 229); +#endif +} + +#endif + +// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING + + +/** + * @brief Get field target_system from waypoint_clear_all message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from waypoint_clear_all message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a waypoint_clear_all message into a struct + * + * @param msg The message to decode + * @param waypoint_clear_all C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg); + waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg); +#else + memcpy(waypoint_clear_all, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_count.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_count.h new file mode 100644 index 0000000000..cfa433338b --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_count.h @@ -0,0 +1,188 @@ +// MESSAGE WAYPOINT_COUNT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44 + +typedef struct __mavlink_waypoint_count_t +{ + uint16_t count; ///< Number of Waypoints in the Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_waypoint_count_t; + +#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN 4 +#define MAVLINK_MSG_ID_44_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT { \ + "WAYPOINT_COUNT", \ + 3, \ + { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_count_t, count) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_count_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_waypoint_count_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_count message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 8); +} + +/** + * @brief Pack a waypoint_count message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 8); +} + +/** + * @brief Encode a waypoint_count struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_count C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count) +{ + return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count); +} + +/** + * @brief Send a waypoint_count message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param count Number of Waypoints in the Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, count); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, buf, 4, 8); +#else + mavlink_waypoint_count_t packet; + packet.count = count; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, (const char *)&packet, 4, 8); +#endif +} + +#endif + +// MESSAGE WAYPOINT_COUNT UNPACKING + + +/** + * @brief Get field target_system from waypoint_count message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from waypoint_count message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field count from waypoint_count message + * + * @return Number of Waypoints in the Sequence + */ +static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a waypoint_count message into a struct + * + * @param msg The message to decode + * @param waypoint_count C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg); + waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg); + waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg); +#else + memcpy(waypoint_count, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_current.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_current.h new file mode 100644 index 0000000000..a2438a4568 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_current.h @@ -0,0 +1,144 @@ +// MESSAGE WAYPOINT_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42 + +typedef struct __mavlink_waypoint_current_t +{ + uint16_t seq; ///< Sequence +} mavlink_waypoint_current_t; + +#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN 2 +#define MAVLINK_MSG_ID_42_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT { \ + "WAYPOINT_CURRENT", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_current_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 2, 101); +} + +/** + * @brief Pack a waypoint_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_current_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 101); +} + +/** + * @brief Encode a waypoint_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current) +{ + return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq); +} + +/** + * @brief Send a waypoint_current message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, buf, 2, 101); +#else + mavlink_waypoint_current_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, (const char *)&packet, 2, 101); +#endif +} + +#endif + +// MESSAGE WAYPOINT_CURRENT UNPACKING + + +/** + * @brief Get field seq from waypoint_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a waypoint_current message into a struct + * + * @param msg The message to decode + * @param waypoint_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg); +#else + memcpy(waypoint_current, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_reached.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_reached.h new file mode 100644 index 0000000000..e1d64b4b66 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_reached.h @@ -0,0 +1,144 @@ +// MESSAGE WAYPOINT_REACHED PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REACHED 46 + +typedef struct __mavlink_waypoint_reached_t +{ + uint16_t seq; ///< Sequence +} mavlink_waypoint_reached_t; + +#define MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN 2 +#define MAVLINK_MSG_ID_46_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED { \ + "WAYPOINT_REACHED", \ + 1, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_reached_t, seq) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_reached message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; + return mavlink_finalize_message(msg, system_id, component_id, 2, 21); +} + +/** + * @brief Pack a waypoint_reached message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_reached_t packet; + packet.seq = seq; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 21); +} + +/** + * @brief Encode a waypoint_reached struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_reached C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached) +{ + return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq); +} + +/** + * @brief Send a waypoint_reached message + * @param chan MAVLink channel to send the message + * + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint16_t(buf, 0, seq); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REACHED, buf, 2, 21); +#else + mavlink_waypoint_reached_t packet; + packet.seq = seq; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REACHED, (const char *)&packet, 2, 21); +#endif +} + +#endif + +// MESSAGE WAYPOINT_REACHED UNPACKING + + +/** + * @brief Get field seq from waypoint_reached message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_reached_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a waypoint_reached message into a struct + * + * @param msg The message to decode + * @param waypoint_reached C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg); +#else + memcpy(waypoint_reached, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request.h new file mode 100644 index 0000000000..b88f4dbfbe --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request.h @@ -0,0 +1,188 @@ +// MESSAGE WAYPOINT_REQUEST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40 + +typedef struct __mavlink_waypoint_request_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_waypoint_request_t; + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN 4 +#define MAVLINK_MSG_ID_40_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST { \ + "WAYPOINT_REQUEST", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_request_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_request_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_waypoint_request_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_request message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; + return mavlink_finalize_message(msg, system_id, component_id, 4, 51); +} + +/** + * @brief Pack a waypoint_request message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 51); +} + +/** + * @brief Encode a waypoint_request struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_request C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request) +{ + return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq); +} + +/** + * @brief Send a waypoint_request message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST, buf, 4, 51); +#else + mavlink_waypoint_request_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST, (const char *)&packet, 4, 51); +#endif +} + +#endif + +// MESSAGE WAYPOINT_REQUEST UNPACKING + + +/** + * @brief Get field target_system from waypoint_request message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from waypoint_request message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from waypoint_request message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a waypoint_request message into a struct + * + * @param msg The message to decode + * @param waypoint_request C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_request->seq = mavlink_msg_waypoint_request_get_seq(msg); + waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg); + waypoint_request->target_component = mavlink_msg_waypoint_request_get_target_component(msg); +#else + memcpy(waypoint_request, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request_list.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request_list.h new file mode 100644 index 0000000000..61e8d834bd --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_request_list.h @@ -0,0 +1,166 @@ +// MESSAGE WAYPOINT_REQUEST_LIST PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST 43 + +typedef struct __mavlink_waypoint_request_list_t +{ + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_waypoint_request_list_t; + +#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN 2 +#define MAVLINK_MSG_ID_43_LEN 2 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST { \ + "WAYPOINT_REQUEST_LIST", \ + 2, \ + { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_list_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_list_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_request_list message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; + return mavlink_finalize_message(msg, system_id, component_id, 2, 213); +} + +/** + * @brief Pack a waypoint_request_list message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 2); +#else + mavlink_waypoint_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 2); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 213); +} + +/** + * @brief Encode a waypoint_request_list struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_request_list C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list) +{ + return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component); +} + +/** + * @brief Send a waypoint_request_list message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[2]; + _mav_put_uint8_t(buf, 0, target_system); + _mav_put_uint8_t(buf, 1, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, buf, 2, 213); +#else + mavlink_waypoint_request_list_t packet; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, (const char *)&packet, 2, 213); +#endif +} + +#endif + +// MESSAGE WAYPOINT_REQUEST_LIST UNPACKING + + +/** + * @brief Get field target_system from waypoint_request_list message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field target_component from waypoint_request_list message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Decode a waypoint_request_list message into a struct + * + * @param msg The message to decode + * @param waypoint_request_list C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg); + waypoint_request_list->target_component = mavlink_msg_waypoint_request_list_get_target_component(msg); +#else + memcpy(waypoint_request_list, _MAV_PAYLOAD(msg), 2); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_set_current.h b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_set_current.h new file mode 100644 index 0000000000..e2c683ee3c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/mavlink_msg_waypoint_set_current.h @@ -0,0 +1,188 @@ +// MESSAGE WAYPOINT_SET_CURRENT PACKING + +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT 41 + +typedef struct __mavlink_waypoint_set_current_t +{ + uint16_t seq; ///< Sequence + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_waypoint_set_current_t; + +#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN 4 +#define MAVLINK_MSG_ID_41_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT { \ + "WAYPOINT_SET_CURRENT", \ + 3, \ + { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_set_current_t, seq) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_set_current_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_waypoint_set_current_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a waypoint_set_current message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 80); +} + +/** + * @brief Pack a waypoint_set_current message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_waypoint_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_waypoint_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 80); +} + +/** + * @brief Encode a waypoint_set_current struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param waypoint_set_current C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current) +{ + return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq); +} + +/** + * @brief Send a waypoint_set_current message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param seq Sequence + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, seq); + _mav_put_uint8_t(buf, 2, target_system); + _mav_put_uint8_t(buf, 3, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, buf, 4, 80); +#else + mavlink_waypoint_set_current_t packet; + packet.seq = seq; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, (const char *)&packet, 4, 80); +#endif +} + +#endif + +// MESSAGE WAYPOINT_SET_CURRENT UNPACKING + + +/** + * @brief Get field target_system from waypoint_set_current message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field target_component from waypoint_set_current message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_waypoint_set_current_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field seq from waypoint_set_current message + * + * @return Sequence + */ +static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a waypoint_set_current message into a struct + * + * @param msg The message to decode + * @param waypoint_set_current C-struct to decode the message contents into + */ +static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current) +{ +#if MAVLINK_NEED_BYTE_SWAP + waypoint_set_current->seq = mavlink_msg_waypoint_set_current_get_seq(msg); + waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg); + waypoint_set_current->target_component = mavlink_msg_waypoint_set_current_get_target_component(msg); +#else + memcpy(waypoint_set_current, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/common/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/common/testsuite.h new file mode 100644 index 0000000000..3c5c9f14ac --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/common/testsuite.h @@ -0,0 +1,3866 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from common.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef COMMON_TESTSUITE_H +#define COMMON_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_common(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_heartbeat_t packet_in = { + 963497464, + 17, + 84, + 151, + 218, + 3, + }; + mavlink_heartbeat_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.custom_mode = packet_in.custom_mode; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.base_mode = packet_in.base_mode; + packet1.system_status = packet_in.system_status; + packet1.mavlink_version = packet_in.mavlink_version; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imagic = MAVLINK_STX; + msg->len = length; + msg->sysid = system_id; + msg->compid = component_id; + // One sequence number per component + msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; + mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; + checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); + + return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + + +/** + * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length, uint8_t crc_extra) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); +} +#else +MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, + uint8_t length) +{ + return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); +} +#endif + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); + +/** + * @brief Finalize a MAVLink message with channel assignment and send + */ +#if MAVLINK_CRC_EXTRA +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, + uint8_t length, uint8_t crc_extra) +#else +MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) +#endif +{ + uint16_t checksum; + uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; + uint8_t ck[2]; + mavlink_status_t *status = mavlink_get_channel_status(chan); + buf[0] = MAVLINK_STX; + buf[1] = length; + buf[2] = status->current_tx_seq; + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + status->current_tx_seq++; + checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&checksum, packet, length); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + ck[0] = (uint8_t)(checksum & 0xFF); + ck[1] = (uint8_t)(checksum >> 8); + + MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); + _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); + _mavlink_send_uart(chan, packet, length); + _mavlink_send_uart(chan, (const char *)ck, 2); + MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +/** + * @brief Pack a message to send it over a serial byte stream + */ +MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) +{ + memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; +} + +union __mavlink_bitfield { + uint8_t uint8; + int8_t int8; + uint16_t uint16; + int16_t int16; + uint32_t uint32; + int32_t int32; +}; + + +MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) +{ + crc_init(&msg->checksum); +} + +MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) +{ + crc_accumulate(c, &msg->checksum); +} + +/** + * This is a convenience function which handles the complete MAVLink parsing. + * the function will parse one byte at a time and return the complete packet once + * it could be successfully decoded. Checksum and other failures will be silently + * ignored. + * + * @param chan ID of the current channel. This allows to parse different channels with this function. + * a channel is not a physical message channel like a serial port, but a logic partition of + * the communication streams in this case. COMM_NB is the limit for the number of channels + * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows + * @param c The char to barse + * + * @param returnMsg NULL if no message could be decoded, the message data else + * @return 0 if no message could be decoded, 1 else + * + * A typical use scenario of this function call is: + * + * @code + * #include // For fixed-width uint8_t type + * + * mavlink_message_t msg; + * int chan = 0; + * + * + * while(serial.bytesAvailable > 0) + * { + * uint8_t byte = serial.getNextByte(); + * if (mavlink_parse_char(chan, byte, &msg)) + * { + * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); + * } + * } + * + * + * @endcode + */ +MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) +{ + static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; + + /* + default message crc function. You can override this per-system to + put this data in a different memory segment + */ +#if MAVLINK_CRC_EXTRA +#ifndef MAVLINK_MESSAGE_CRC + static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] +#endif +#endif + + mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status + int bufferIndex = 0; + + status->msg_received = 0; + + switch (status->parse_state) + { + case MAVLINK_PARSE_STATE_UNINIT: + case MAVLINK_PARSE_STATE_IDLE: + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + break; + + case MAVLINK_PARSE_STATE_GOT_STX: + if (status->msg_received +/* Support shorter buffers than the + default maximum packet size */ +#if (MAVLINK_MAX_PAYLOAD_LEN < 255) + || c > MAVLINK_MAX_PAYLOAD_LEN +#endif + ) + { + status->buffer_overrun++; + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + } + else + { + // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 + rxmsg->len = c; + status->packet_idx = 0; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; + } + break; + + case MAVLINK_PARSE_STATE_GOT_LENGTH: + rxmsg->seq = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; + break; + + case MAVLINK_PARSE_STATE_GOT_SEQ: + rxmsg->sysid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; + break; + + case MAVLINK_PARSE_STATE_GOT_SYSID: + rxmsg->compid = c; + mavlink_update_checksum(rxmsg, c); + status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; + break; + + case MAVLINK_PARSE_STATE_GOT_COMPID: + rxmsg->msgid = c; + mavlink_update_checksum(rxmsg, c); + if (rxmsg->len == 0) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; + } + break; + + case MAVLINK_PARSE_STATE_GOT_MSGID: + _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; + mavlink_update_checksum(rxmsg, c); + if (status->packet_idx == rxmsg->len) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; + } + break; + + case MAVLINK_PARSE_STATE_GOT_PAYLOAD: +#if MAVLINK_CRC_EXTRA + mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); +#endif + if (c != (rxmsg->checksum & 0xFF)) { + // Check first checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + } + else + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + } + break; + + case MAVLINK_PARSE_STATE_GOT_CRC1: + if (c != (rxmsg->checksum >> 8)) { + // Check second checksum byte + status->parse_error++; + status->msg_received = 0; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + rxmsg->len = 0; + mavlink_start_checksum(rxmsg); + } + } + else + { + // Successfully got message + status->msg_received = 1; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); + } + break; + } + + bufferIndex++; + // If a message has been sucessfully decoded, check index + if (status->msg_received == 1) + { + //while(status->current_seq != rxmsg->seq) + //{ + // status->packet_rx_drop_count++; + // status->current_seq++; + //} + status->current_rx_seq = rxmsg->seq; + // Initial condition: If no packet has been received so far, drop count is undefined + if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; + // Count this packet as received + status->packet_rx_success_count++; + } + + r_mavlink_status->current_rx_seq = status->current_rx_seq+1; + r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; + r_mavlink_status->packet_rx_drop_count = status->parse_error; + status->parse_error = 0; + return status->msg_received; +} + +/** + * @brief Put a bitfield of length 1-32 bit into the buffer + * + * @param b the value to add, will be encoded in the bitfield + * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. + * @param packet_index the position in the packet (the index of the first byte to use) + * @param bit_index the position in the byte (the index of the first bit to use) + * @param buffer packet buffer to write into + * @return new position of the last used byte in the buffer + */ +MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) +{ + uint16_t bits_remain = bits; + // Transform number into network order + int32_t v; + uint8_t i_bit_index, i_byte_index, curr_bits_n; +#if MAVLINK_NEED_BYTE_SWAP + union { + int32_t i; + uint8_t b[4]; + } bin, bout; + bin.i = b; + bout.b[0] = bin.b[3]; + bout.b[1] = bin.b[2]; + bout.b[2] = bin.b[1]; + bout.b[3] = bin.b[0]; + v = bout.i; +#else + v = b; +#endif + + // buffer in + // 01100000 01000000 00000000 11110001 + // buffer out + // 11110001 00000000 01000000 01100000 + + // Existing partly filled byte (four free slots) + // 0111xxxx + + // Mask n free bits + // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 + // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 + + // Shift n bits into the right position + // out = in >> n; + + // Mask and shift bytes + i_bit_index = bit_index; + i_byte_index = packet_index; + if (bit_index > 0) + { + // If bits were available at start, they were available + // in the byte before the current index + i_byte_index--; + } + + // While bits have not been packed yet + while (bits_remain > 0) + { + // Bits still have to be packed + // there can be more than 8 bits, so + // we might have to pack them into more than one byte + + // First pack everything we can into the current 'open' byte + //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 + //FIXME + if (bits_remain <= (uint8_t)(8 - i_bit_index)) + { + // Enough space + curr_bits_n = (uint8_t)bits_remain; + } + else + { + curr_bits_n = (8 - i_bit_index); + } + + // Pack these n bits into the current byte + // Mask out whatever was at that position with ones (xxx11111) + buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); + // Put content to this position, by masking out the non-used part + buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); + + // Increment the bit index + i_bit_index += curr_bits_n; + + // Now proceed to the next byte, if necessary + bits_remain -= curr_bits_n; + if (bits_remain > 0) + { + // Offer another 8 bits / one byte + i_byte_index++; + i_bit_index = 0; + } + } + + *r_bit_index = i_bit_index; + // If a partly filled byte is present, mark this as consumed + if (i_bit_index != 7) i_byte_index++; + return i_byte_index - packet_index; +} + +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +// To make MAVLink work on your MCU, define comm_send_ch() if you wish +// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a +// whole packet at a time + +/* + +#include "mavlink_types.h" + +void comm_send_ch(mavlink_channel_t chan, uint8_t ch) +{ + if (chan == MAVLINK_COMM_0) + { + uart0_transmit(ch); + } + if (chan == MAVLINK_COMM_1) + { + uart1_transmit(ch); + } +} + */ + +MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) +{ +#ifdef MAVLINK_SEND_UART_BYTES + /* this is the more efficient approach, if the platform + defines it */ + MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); +#else + /* fallback to one byte at a time */ + uint16_t i; + for (i = 0; i < len; i++) { + comm_send_ch(chan, (uint8_t)buf[i]); + } +#endif +} +#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS + +#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/libraries/GCS_MAVLink/include_v1.0/mavlink_types.h b/libraries/GCS_MAVLink/include_v1.0/mavlink_types.h new file mode 100644 index 0000000000..03faf594fe --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/mavlink_types.h @@ -0,0 +1,182 @@ +#ifndef MAVLINK_TYPES_H_ +#define MAVLINK_TYPES_H_ + +#include + +enum MAV_ACTION +{ + MAV_ACTION_HOLD = 0, + MAV_ACTION_MOTORS_START = 1, + MAV_ACTION_LAUNCH = 2, + MAV_ACTION_RETURN = 3, + MAV_ACTION_EMCY_LAND = 4, + MAV_ACTION_EMCY_KILL = 5, + MAV_ACTION_CONFIRM_KILL = 6, + MAV_ACTION_CONTINUE = 7, + MAV_ACTION_MOTORS_STOP = 8, + MAV_ACTION_HALT = 9, + MAV_ACTION_SHUTDOWN = 10, + MAV_ACTION_REBOOT = 11, + MAV_ACTION_SET_MANUAL = 12, + MAV_ACTION_SET_AUTO = 13, + MAV_ACTION_STORAGE_READ = 14, + MAV_ACTION_STORAGE_WRITE = 15, + MAV_ACTION_CALIBRATE_RC = 16, + MAV_ACTION_CALIBRATE_GYRO = 17, + MAV_ACTION_CALIBRATE_MAG = 18, + MAV_ACTION_CALIBRATE_ACC = 19, + MAV_ACTION_CALIBRATE_PRESSURE = 20, + MAV_ACTION_REC_START = 21, + MAV_ACTION_REC_PAUSE = 22, + MAV_ACTION_REC_STOP = 23, + MAV_ACTION_TAKEOFF = 24, + MAV_ACTION_NAVIGATE = 25, + MAV_ACTION_LAND = 26, + MAV_ACTION_LOITER = 27, + MAV_ACTION_SET_ORIGIN = 28, + MAV_ACTION_RELAY_ON = 29, + MAV_ACTION_RELAY_OFF = 30, + MAV_ACTION_GET_IMAGE = 31, + MAV_ACTION_VIDEO_START = 32, + MAV_ACTION_VIDEO_STOP = 33, + MAV_ACTION_RESET_MAP = 34, + MAV_ACTION_RESET_PLAN = 35, + MAV_ACTION_DELAY_BEFORE_COMMAND = 36, + MAV_ACTION_ASCEND_AT_RATE = 37, + MAV_ACTION_CHANGE_MODE = 38, + MAV_ACTION_LOITER_MAX_TURNS = 39, + MAV_ACTION_LOITER_MAX_TIME = 40, + MAV_ACTION_START_HILSIM = 41, + MAV_ACTION_STOP_HILSIM = 42, + MAV_ACTION_NB ///< Number of MAV actions +}; + +#ifndef MAVLINK_MAX_PAYLOAD_LEN +// it is possible to override this, but be careful! +#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length +#endif + +#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) +#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum +#define MAVLINK_NUM_CHECKSUM_BYTES 2 +#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) + +#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length + +typedef struct param_union { + union { + float param_float; + int32_t param_int32; + uint32_t param_uint32; + }; + uint8_t type; +} mavlink_param_union_t; + +typedef struct __mavlink_system { + uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function + uint8_t type; ///< Unused, can be used by user to store the system's type + uint8_t state; ///< Unused, can be used by user to store the system's state + uint8_t mode; ///< Unused, can be used by user to store the system's mode + uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode +} mavlink_system_t; + +typedef struct __mavlink_message { + uint16_t checksum; /// sent at end of packet + uint8_t magic; ///< protocol magic marker + uint8_t len; ///< Length of payload + uint8_t seq; ///< Sequence of packet + uint8_t sysid; ///< ID of message sender system/aircraft + uint8_t compid; ///< ID of the message sender component + uint8_t msgid; ///< ID of message in payload + uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; +} mavlink_message_t; + +typedef enum { + MAVLINK_TYPE_CHAR = 0, + MAVLINK_TYPE_UINT8_T = 1, + MAVLINK_TYPE_INT8_T = 2, + MAVLINK_TYPE_UINT16_T = 3, + MAVLINK_TYPE_INT16_T = 4, + MAVLINK_TYPE_UINT32_T = 5, + MAVLINK_TYPE_INT32_T = 6, + MAVLINK_TYPE_UINT64_T = 7, + MAVLINK_TYPE_INT64_T = 8, + MAVLINK_TYPE_FLOAT = 9, + MAVLINK_TYPE_DOUBLE = 10 +} mavlink_message_type_t; + +#define MAVLINK_MAX_FIELDS 64 + +typedef struct __mavlink_field_info { + const char *name; // name of this field + const char *print_format; // printing format hint, or NULL + mavlink_message_type_t type; // type of this field + unsigned array_length; // if non-zero, field is an array + unsigned wire_offset; // offset of each field in the payload + unsigned structure_offset; // offset in a C structure +} mavlink_field_info_t; + +// note that in this structure the order of fields is the order +// in the XML file, not necessary the wire order +typedef struct __mavlink_message_info { + const char *name; // name of the message + unsigned num_fields; // how many fields in this message + mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information +} mavlink_message_info_t; + +#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) + +// checksum is immediately after the payload bytes +#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) +#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) + +typedef enum { + MAVLINK_COMM_0, + MAVLINK_COMM_1, + MAVLINK_COMM_2, + MAVLINK_COMM_3 +} mavlink_channel_t; + +/* + * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number + * of buffers they will use. If more are used, then the result will be + * a stack overrun + */ +#ifndef MAVLINK_COMM_NUM_BUFFERS +#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) +# define MAVLINK_COMM_NUM_BUFFERS 16 +#else +# define MAVLINK_COMM_NUM_BUFFERS 4 +#endif +#endif + +typedef enum { + MAVLINK_PARSE_STATE_UNINIT=0, + MAVLINK_PARSE_STATE_IDLE, + MAVLINK_PARSE_STATE_GOT_STX, + MAVLINK_PARSE_STATE_GOT_SEQ, + MAVLINK_PARSE_STATE_GOT_LENGTH, + MAVLINK_PARSE_STATE_GOT_SYSID, + MAVLINK_PARSE_STATE_GOT_COMPID, + MAVLINK_PARSE_STATE_GOT_MSGID, + MAVLINK_PARSE_STATE_GOT_PAYLOAD, + MAVLINK_PARSE_STATE_GOT_CRC1 +} mavlink_parse_state_t; ///< The state machine for the comm parser + +typedef struct __mavlink_status { + uint8_t msg_received; ///< Number of received messages + uint8_t buffer_overrun; ///< Number of buffer overruns + uint8_t parse_error; ///< Number of parse errors + mavlink_parse_state_t parse_state; ///< Parsing state machine + uint8_t packet_idx; ///< Index in current packet + uint8_t current_rx_seq; ///< Sequence number of last packet received + uint8_t current_tx_seq; ///< Sequence number of last packet sent + uint16_t packet_rx_success_count; ///< Received packets + uint16_t packet_rx_drop_count; ///< Number of packet drops +} mavlink_status_t; + +#define MAVLINK_BIG_ENDIAN 0 +#define MAVLINK_LITTLE_ENDIAN 1 + +#endif /* MAVLINK_TYPES_H_ */ diff --git a/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink.h b/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink.h new file mode 100644 index 0000000000..0a759b6185 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink.h @@ -0,0 +1,27 @@ +/** @file + * @brief MAVLink comm protocol built from minimal.xml + * @see http://pixhawk.ethz.ch/software/mavlink + */ +#ifndef MAVLINK_H +#define MAVLINK_H + +#ifndef MAVLINK_STX +#define MAVLINK_STX 254 +#endif + +#ifndef MAVLINK_ENDIAN +#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN +#endif + +#ifndef MAVLINK_ALIGNED_FIELDS +#define MAVLINK_ALIGNED_FIELDS 1 +#endif + +#ifndef MAVLINK_CRC_EXTRA +#define MAVLINK_CRC_EXTRA 1 +#endif + +#include "version.h" +#include "minimal.h" + +#endif // MAVLINK_H diff --git a/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink_msg_heartbeat.h b/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink_msg_heartbeat.h new file mode 100644 index 0000000000..103b08be8a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/minimal/mavlink_msg_heartbeat.h @@ -0,0 +1,251 @@ +// MESSAGE HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_HEARTBEAT 0 + +typedef struct __mavlink_heartbeat_t +{ + uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + uint8_t autopilot; ///< Autopilot type / class. defined in MAV_CLASS ENUM + uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM + uint8_t mavlink_version; ///< MAVLink version +} mavlink_heartbeat_t; + +#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 +#define MAVLINK_MSG_ID_0_LEN 9 + + + +#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ + "HEARTBEAT", \ + 6, \ + { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ + { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ + { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ + { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ + { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ + } \ +} + + +/** + * @brief Pack a heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 2); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 2; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message(msg, system_id, component_id, 9, 50); +} + +/** + * @brief Pack a heartbeat message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 2); + + memcpy(_MAV_PAYLOAD(msg), buf, 9); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 2; + + memcpy(_MAV_PAYLOAD(msg), &packet, 9); +#endif + + msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50); +} + +/** + * @brief Encode a heartbeat struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) +{ + return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); +} + +/** + * @brief Send a heartbeat message + * @param chan MAVLink channel to send the message + * + * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM + * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + * @param system_status System status flag, see MAV_STATUS ENUM + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[9]; + _mav_put_uint32_t(buf, 0, custom_mode); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, autopilot); + _mav_put_uint8_t(buf, 6, base_mode); + _mav_put_uint8_t(buf, 7, system_status); + _mav_put_uint8_t(buf, 8, 2); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50); +#else + mavlink_heartbeat_t packet; + packet.custom_mode = custom_mode; + packet.type = type; + packet.autopilot = autopilot; + packet.base_mode = base_mode; + packet.system_status = system_status; + packet.mavlink_version = 2; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50); +#endif +} + +#endif + +// MESSAGE HEARTBEAT UNPACKING + + +/** + * @brief Get field type from heartbeat message + * + * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + */ +static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field autopilot from heartbeat message + * + * @return Autopilot type / class. defined in MAV_CLASS ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field base_mode from heartbeat message + * + * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + */ +static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field custom_mode from heartbeat message + * + * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + */ +static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field system_status from heartbeat message + * + * @return System status flag, see MAV_STATUS ENUM + */ +static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Get field mavlink_version from heartbeat message + * + * @return MAVLink version + */ +static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Decode a heartbeat message into a struct + * + * @param msg The message to decode + * @param heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); + heartbeat->type = mavlink_msg_heartbeat_get_type(msg); + heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); + heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); + heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); + heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); +#else + memcpy(heartbeat, _MAV_PAYLOAD(msg), 9); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/minimal/minimal.h b/libraries/GCS_MAVLink/include_v1.0/minimal/minimal.h new file mode 100644 index 0000000000..895c79d0a4 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/minimal/minimal.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from minimal.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef MINIMAL_H +#define MINIMAL_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_MINIMAL + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_heartbeat.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // MINIMAL_H diff --git a/libraries/GCS_MAVLink/include_v1.0/minimal/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/minimal/testsuite.h new file mode 100644 index 0000000000..1758c912cf --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/minimal/testsuite.h @@ -0,0 +1,88 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from minimal.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef MINIMAL_TESTSUITE_H +#define MINIMAL_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_minimal(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_heartbeat_t packet_in = { + 963497464, + 17, + 84, + 151, + 218, + 2, + }; + mavlink_heartbeat_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.custom_mode = packet_in.custom_mode; + packet1.type = packet_in.type; + packet1.autopilot = packet_in.autopilot; + packet1.base_mode = packet_in.base_mode; + packet1.system_status = packet_in.system_status; + packet1.mavlink_version = packet_in.mavlink_version; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); + mavlink_msg_heartbeat_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 21, 254); +} + +/** + * @brief Pack a attitude_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + memcpy(_MAV_PAYLOAD(msg), buf, 21); +#else + mavlink_attitude_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + memcpy(_MAV_PAYLOAD(msg), &packet, 21); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 254); +} + +/** + * @brief Encode a attitude_control struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control) +{ + return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual); +} + +/** + * @brief Send a attitude_control message + * @param chan MAVLink channel to send the message + * + * @param target The system to be controlled + * @param roll roll + * @param pitch pitch + * @param yaw yaw + * @param thrust thrust + * @param roll_manual roll control enabled auto:0, manual:1 + * @param pitch_manual pitch auto:0, manual:1 + * @param yaw_manual yaw auto:0, manual:1 + * @param thrust_manual thrust auto:0, manual:1 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[21]; + _mav_put_float(buf, 0, roll); + _mav_put_float(buf, 4, pitch); + _mav_put_float(buf, 8, yaw); + _mav_put_float(buf, 12, thrust); + _mav_put_uint8_t(buf, 16, target); + _mav_put_uint8_t(buf, 17, roll_manual); + _mav_put_uint8_t(buf, 18, pitch_manual); + _mav_put_uint8_t(buf, 19, yaw_manual); + _mav_put_uint8_t(buf, 20, thrust_manual); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, 21, 254); +#else + mavlink_attitude_control_t packet; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.thrust = thrust; + packet.target = target; + packet.roll_manual = roll_manual; + packet.pitch_manual = pitch_manual; + packet.yaw_manual = yaw_manual; + packet.thrust_manual = thrust_manual; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, 21, 254); +#endif +} + +#endif + +// MESSAGE ATTITUDE_CONTROL UNPACKING + + +/** + * @brief Get field target from attitude_control message + * + * @return The system to be controlled + */ +static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field roll from attitude_control message + * + * @return roll + */ +static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field pitch from attitude_control message + * + * @return pitch + */ +static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field yaw from attitude_control message + * + * @return yaw + */ +static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field thrust from attitude_control message + * + * @return thrust + */ +static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field roll_manual from attitude_control message + * + * @return roll control enabled auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_roll_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field pitch_manual from attitude_control message + * + * @return pitch auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_pitch_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field yaw_manual from attitude_control message + * + * @return yaw auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_yaw_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field thrust_manual from attitude_control message + * + * @return thrust auto:0, manual:1 + */ +static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Decode a attitude_control message into a struct + * + * @param msg The message to decode + * @param attitude_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg); + attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg); + attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg); + attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg); + attitude_control->target = mavlink_msg_attitude_control_get_target(msg); + attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg); + attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg); + attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); + attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg); +#else + memcpy(attitude_control, _MAV_PAYLOAD(msg), 21); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_brief_feature.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_brief_feature.h new file mode 100644 index 0000000000..3e6b374c2a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_brief_feature.h @@ -0,0 +1,292 @@ +// MESSAGE BRIEF_FEATURE PACKING + +#define MAVLINK_MSG_ID_BRIEF_FEATURE 195 + +typedef struct __mavlink_brief_feature_t +{ + float x; ///< x position in m + float y; ///< y position in m + float z; ///< z position in m + float response; ///< Harris operator response at this location + uint16_t size; ///< Size in pixels + uint16_t orientation; ///< Orientation + uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true + uint8_t descriptor[32]; ///< Descriptor +} mavlink_brief_feature_t; + +#define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53 +#define MAVLINK_MSG_ID_195_LEN 53 + +#define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32 + +#define MAVLINK_MESSAGE_INFO_BRIEF_FEATURE { \ + "BRIEF_FEATURE", \ + 8, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_brief_feature_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_brief_feature_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_brief_feature_t, z) }, \ + { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_brief_feature_t, response) }, \ + { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_brief_feature_t, size) }, \ + { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_brief_feature_t, orientation) }, \ + { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \ + { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_brief_feature_t, descriptor) }, \ + } \ +} + + +/** + * @brief Pack a brief_feature message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[53]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 53); +#else + mavlink_brief_feature_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.response = response; + packet.size = size; + packet.orientation = orientation; + packet.orientation_assignment = orientation_assignment; + memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 53); +#endif + + msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; + return mavlink_finalize_message(msg, system_id, component_id, 53, 88); +} + +/** + * @brief Pack a brief_feature message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float x,float y,float z,uint8_t orientation_assignment,uint16_t size,uint16_t orientation,const uint8_t *descriptor,float response) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[53]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + memcpy(_MAV_PAYLOAD(msg), buf, 53); +#else + mavlink_brief_feature_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.response = response; + packet.size = size; + packet.orientation = orientation; + packet.orientation_assignment = orientation_assignment; + memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); + memcpy(_MAV_PAYLOAD(msg), &packet, 53); +#endif + + msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53, 88); +} + +/** + * @brief Encode a brief_feature struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param brief_feature C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature) +{ + return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response); +} + +/** + * @brief Send a brief_feature message + * @param chan MAVLink channel to send the message + * + * @param x x position in m + * @param y y position in m + * @param z z position in m + * @param orientation_assignment Orientation assignment 0: false, 1:true + * @param size Size in pixels + * @param orientation Orientation + * @param descriptor Descriptor + * @param response Harris operator response at this location + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[53]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, response); + _mav_put_uint16_t(buf, 16, size); + _mav_put_uint16_t(buf, 18, orientation); + _mav_put_uint8_t(buf, 20, orientation_assignment); + _mav_put_uint8_t_array(buf, 21, descriptor, 32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, 53, 88); +#else + mavlink_brief_feature_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.response = response; + packet.size = size; + packet.orientation = orientation; + packet.orientation_assignment = orientation_assignment; + memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, 53, 88); +#endif +} + +#endif + +// MESSAGE BRIEF_FEATURE UNPACKING + + +/** + * @brief Get field x from brief_feature message + * + * @return x position in m + */ +static inline float mavlink_msg_brief_feature_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from brief_feature message + * + * @return y position in m + */ +static inline float mavlink_msg_brief_feature_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from brief_feature message + * + * @return z position in m + */ +static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field orientation_assignment from brief_feature message + * + * @return Orientation assignment 0: false, 1:true + */ +static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 20); +} + +/** + * @brief Get field size from brief_feature message + * + * @return Size in pixels + */ +static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field orientation from brief_feature message + * + * @return Orientation + */ +static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 18); +} + +/** + * @brief Get field descriptor from brief_feature message + * + * @return Descriptor + */ +static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t *descriptor) +{ + return _MAV_RETURN_uint8_t_array(msg, descriptor, 32, 21); +} + +/** + * @brief Get field response from brief_feature message + * + * @return Harris operator response at this location + */ +static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a brief_feature message into a struct + * + * @param msg The message to decode + * @param brief_feature C-struct to decode the message contents into + */ +static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature) +{ +#if MAVLINK_NEED_BYTE_SWAP + brief_feature->x = mavlink_msg_brief_feature_get_x(msg); + brief_feature->y = mavlink_msg_brief_feature_get_y(msg); + brief_feature->z = mavlink_msg_brief_feature_get_z(msg); + brief_feature->response = mavlink_msg_brief_feature_get_response(msg); + brief_feature->size = mavlink_msg_brief_feature_get_size(msg); + brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg); + brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); + mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor); +#else + memcpy(brief_feature, _MAV_PAYLOAD(msg), 53); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h new file mode 100644 index 0000000000..dccaace75b --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_data_transmission_handshake.h @@ -0,0 +1,232 @@ +// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 193 + +typedef struct __mavlink_data_transmission_handshake_t +{ + uint32_t size; ///< total data size in bytes (set on ACK only) + uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + uint8_t packets; ///< number of packets beeing sent (set on ACK only) + uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + uint8_t jpg_quality; ///< JPEG quality out of [1,100] +} mavlink_data_transmission_handshake_t; + +#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 8 +#define MAVLINK_MSG_ID_193_LEN 8 + + + +#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ + "DATA_TRANSMISSION_HANDSHAKE", \ + 5, \ + { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, type) }, \ + { "packets", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ + { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ + { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ + } \ +} + + +/** + * @brief Pack a data_transmission_handshake message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, packets); + _mav_put_uint8_t(buf, 6, payload); + _mav_put_uint8_t(buf, 7, jpg_quality); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.type = type; + packet.packets = packets; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; + return mavlink_finalize_message(msg, system_id, component_id, 8, 148); +} + +/** + * @brief Pack a data_transmission_handshake message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint32_t size,uint8_t packets,uint8_t payload,uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, packets); + _mav_put_uint8_t(buf, 6, payload); + _mav_put_uint8_t(buf, 7, jpg_quality); + + memcpy(_MAV_PAYLOAD(msg), buf, 8); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.type = type; + packet.packets = packets; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + memcpy(_MAV_PAYLOAD(msg), &packet, 8); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 148); +} + +/** + * @brief Encode a data_transmission_handshake struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_transmission_handshake C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ + return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); +} + +/** + * @brief Send a data_transmission_handshake message + * @param chan MAVLink channel to send the message + * + * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + * @param size total data size in bytes (set on ACK only) + * @param packets number of packets beeing sent (set on ACK only) + * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + * @param jpg_quality JPEG quality out of [1,100] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[8]; + _mav_put_uint32_t(buf, 0, size); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 5, packets); + _mav_put_uint8_t(buf, 6, payload); + _mav_put_uint8_t(buf, 7, jpg_quality); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, 8, 148); +#else + mavlink_data_transmission_handshake_t packet; + packet.size = size; + packet.type = type; + packet.packets = packets; + packet.payload = payload; + packet.jpg_quality = jpg_quality; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, 8, 148); +#endif +} + +#endif + +// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING + + +/** + * @brief Get field type from data_transmission_handshake message + * + * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field size from data_transmission_handshake message + * + * @return total data size in bytes (set on ACK only) + */ +static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field packets from data_transmission_handshake message + * + * @return number of packets beeing sent (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field payload from data_transmission_handshake message + * + * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Get field jpg_quality from data_transmission_handshake message + * + * @return JPEG quality out of [1,100] + */ +static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 7); +} + +/** + * @brief Decode a data_transmission_handshake message into a struct + * + * @param msg The message to decode + * @param data_transmission_handshake C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); + data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); + data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); + data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); + data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); +#else + memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), 8); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_encapsulated_data.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_encapsulated_data.h new file mode 100644 index 0000000000..dcd65c2f44 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_encapsulated_data.h @@ -0,0 +1,160 @@ +// MESSAGE ENCAPSULATED_DATA PACKING + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 194 + +typedef struct __mavlink_encapsulated_data_t +{ + uint16_t seqnr; ///< sequence number (starting with 0 on every transmission) + uint8_t data[253]; ///< image data bytes +} mavlink_encapsulated_data_t; + +#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 +#define MAVLINK_MSG_ID_194_LEN 255 + +#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 + +#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ + "ENCAPSULATED_DATA", \ + 2, \ + { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ + { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ + } \ +} + + +/** + * @brief Pack a encapsulated_data message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD(msg), buf, 255); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD(msg), &packet, 255); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; + return mavlink_finalize_message(msg, system_id, component_id, 255, 223); +} + +/** + * @brief Pack a encapsulated_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t seqnr,const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + memcpy(_MAV_PAYLOAD(msg), buf, 255); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + memcpy(packet.data, data, sizeof(uint8_t)*253); + memcpy(_MAV_PAYLOAD(msg), &packet, 255); +#endif + + msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 223); +} + +/** + * @brief Encode a encapsulated_data struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param encapsulated_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) +{ + return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); +} + +/** + * @brief Send a encapsulated_data message + * @param chan MAVLink channel to send the message + * + * @param seqnr sequence number (starting with 0 on every transmission) + * @param data image data bytes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_uint16_t(buf, 0, seqnr); + _mav_put_uint8_t_array(buf, 2, data, 253); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, 255, 223); +#else + mavlink_encapsulated_data_t packet; + packet.seqnr = seqnr; + memcpy(packet.data, data, sizeof(uint8_t)*253); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, 255, 223); +#endif +} + +#endif + +// MESSAGE ENCAPSULATED_DATA UNPACKING + + +/** + * @brief Get field seqnr from encapsulated_data message + * + * @return sequence number (starting with 0 on every transmission) + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field data from encapsulated_data message + * + * @return image data bytes + */ +static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) +{ + return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); +} + +/** + * @brief Decode a encapsulated_data message into a struct + * + * @param msg The message to decode + * @param encapsulated_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); + mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); +#else + memcpy(encapsulated_data, _MAV_PAYLOAD(msg), 255); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_available.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_available.h new file mode 100644 index 0000000000..cdbdf466fd --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_available.h @@ -0,0 +1,628 @@ +// MESSAGE IMAGE_AVAILABLE PACKING + +#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 154 + +typedef struct __mavlink_image_available_t +{ + uint64_t cam_id; ///< Camera id + uint64_t timestamp; ///< Timestamp + uint64_t valid_until; ///< Until which timestamp this buffer will stay valid + uint32_t img_seq; ///< The image sequence number + uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 + uint32_t key; ///< Shared memory area key + uint32_t exposure; ///< Exposure time, in microseconds + float gain; ///< Camera gain + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + float local_z; ///< Local frame Z coordinate (height over ground) + float lat; ///< GPS X coordinate + float lon; ///< GPS Y coordinate + float alt; ///< Global frame altitude + float ground_x; ///< Ground truth X + float ground_y; ///< Ground truth Y + float ground_z; ///< Ground truth Z + uint16_t width; ///< Image width + uint16_t height; ///< Image height + uint16_t depth; ///< Image depth + uint8_t cam_no; ///< Camera # (starts with 0) + uint8_t channels; ///< Image channels +} mavlink_image_available_t; + +#define MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN 92 +#define MAVLINK_MSG_ID_154_LEN 92 + + + +#define MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE { \ + "IMAGE_AVAILABLE", \ + 23, \ + { { "cam_id", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_available_t, cam_id) }, \ + { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_image_available_t, timestamp) }, \ + { "valid_until", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_image_available_t, valid_until) }, \ + { "img_seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_image_available_t, img_seq) }, \ + { "img_buf_index", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_image_available_t, img_buf_index) }, \ + { "key", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_image_available_t, key) }, \ + { "exposure", NULL, MAVLINK_TYPE_UINT32_T, 0, 36, offsetof(mavlink_image_available_t, exposure) }, \ + { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_available_t, gain) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_available_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_available_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_image_available_t, yaw) }, \ + { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_image_available_t, local_z) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_image_available_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_image_available_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_image_available_t, alt) }, \ + { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_image_available_t, ground_x) }, \ + { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_image_available_t, ground_y) }, \ + { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_image_available_t, ground_z) }, \ + { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_image_available_t, width) }, \ + { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_image_available_t, height) }, \ + { "depth", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_image_available_t, depth) }, \ + { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_image_available_t, cam_no) }, \ + { "channels", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_image_available_t, channels) }, \ + } \ +} + + +/** + * @brief Pack a image_available message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[92]; + _mav_put_uint64_t(buf, 0, cam_id); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + memcpy(_MAV_PAYLOAD(msg), buf, 92); +#else + mavlink_image_available_t packet; + packet.cam_id = cam_id; + packet.timestamp = timestamp; + packet.valid_until = valid_until; + packet.img_seq = img_seq; + packet.img_buf_index = img_buf_index; + packet.key = key; + packet.exposure = exposure; + packet.gain = gain; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; + + memcpy(_MAV_PAYLOAD(msg), &packet, 92); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; + return mavlink_finalize_message(msg, system_id, component_id, 92, 224); +} + +/** + * @brief Pack a image_available message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t cam_id,uint8_t cam_no,uint64_t timestamp,uint64_t valid_until,uint32_t img_seq,uint32_t img_buf_index,uint16_t width,uint16_t height,uint16_t depth,uint8_t channels,uint32_t key,uint32_t exposure,float gain,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[92]; + _mav_put_uint64_t(buf, 0, cam_id); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + memcpy(_MAV_PAYLOAD(msg), buf, 92); +#else + mavlink_image_available_t packet; + packet.cam_id = cam_id; + packet.timestamp = timestamp; + packet.valid_until = valid_until; + packet.img_seq = img_seq; + packet.img_buf_index = img_buf_index; + packet.key = key; + packet.exposure = exposure; + packet.gain = gain; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; + + memcpy(_MAV_PAYLOAD(msg), &packet, 92); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 92, 224); +} + +/** + * @brief Encode a image_available struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param image_available C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) +{ + return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z); +} + +/** + * @brief Send a image_available message + * @param chan MAVLink channel to send the message + * + * @param cam_id Camera id + * @param cam_no Camera # (starts with 0) + * @param timestamp Timestamp + * @param valid_until Until which timestamp this buffer will stay valid + * @param img_seq The image sequence number + * @param img_buf_index Position of the image in the buffer, starts with 0 + * @param width Image width + * @param height Image height + * @param depth Image depth + * @param channels Image channels + * @param key Shared memory area key + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[92]; + _mav_put_uint64_t(buf, 0, cam_id); + _mav_put_uint64_t(buf, 8, timestamp); + _mav_put_uint64_t(buf, 16, valid_until); + _mav_put_uint32_t(buf, 24, img_seq); + _mav_put_uint32_t(buf, 28, img_buf_index); + _mav_put_uint32_t(buf, 32, key); + _mav_put_uint32_t(buf, 36, exposure); + _mav_put_float(buf, 40, gain); + _mav_put_float(buf, 44, roll); + _mav_put_float(buf, 48, pitch); + _mav_put_float(buf, 52, yaw); + _mav_put_float(buf, 56, local_z); + _mav_put_float(buf, 60, lat); + _mav_put_float(buf, 64, lon); + _mav_put_float(buf, 68, alt); + _mav_put_float(buf, 72, ground_x); + _mav_put_float(buf, 76, ground_y); + _mav_put_float(buf, 80, ground_z); + _mav_put_uint16_t(buf, 84, width); + _mav_put_uint16_t(buf, 86, height); + _mav_put_uint16_t(buf, 88, depth); + _mav_put_uint8_t(buf, 90, cam_no); + _mav_put_uint8_t(buf, 91, channels); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, 92, 224); +#else + mavlink_image_available_t packet; + packet.cam_id = cam_id; + packet.timestamp = timestamp; + packet.valid_until = valid_until; + packet.img_seq = img_seq; + packet.img_buf_index = img_buf_index; + packet.key = key; + packet.exposure = exposure; + packet.gain = gain; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + packet.width = width; + packet.height = height; + packet.depth = depth; + packet.cam_no = cam_no; + packet.channels = channels; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, 92, 224); +#endif +} + +#endif + +// MESSAGE IMAGE_AVAILABLE UNPACKING + + +/** + * @brief Get field cam_id from image_available message + * + * @return Camera id + */ +static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field cam_no from image_available message + * + * @return Camera # (starts with 0) + */ +static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 90); +} + +/** + * @brief Get field timestamp from image_available message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 8); +} + +/** + * @brief Get field valid_until from image_available message + * + * @return Until which timestamp this buffer will stay valid + */ +static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 16); +} + +/** + * @brief Get field img_seq from image_available message + * + * @return The image sequence number + */ +static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 24); +} + +/** + * @brief Get field img_buf_index from image_available message + * + * @return Position of the image in the buffer, starts with 0 + */ +static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 28); +} + +/** + * @brief Get field width from image_available message + * + * @return Image width + */ +static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 84); +} + +/** + * @brief Get field height from image_available message + * + * @return Image height + */ +static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 86); +} + +/** + * @brief Get field depth from image_available message + * + * @return Image depth + */ +static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 88); +} + +/** + * @brief Get field channels from image_available message + * + * @return Image channels + */ +static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 91); +} + +/** + * @brief Get field key from image_available message + * + * @return Shared memory area key + */ +static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 32); +} + +/** + * @brief Get field exposure from image_available message + * + * @return Exposure time, in microseconds + */ +static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 36); +} + +/** + * @brief Get field gain from image_available message + * + * @return Camera gain + */ +static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field roll from image_available message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field pitch from image_available message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Get field yaw from image_available message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 52); +} + +/** + * @brief Get field local_z from image_available message + * + * @return Local frame Z coordinate (height over ground) + */ +static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 56); +} + +/** + * @brief Get field lat from image_available message + * + * @return GPS X coordinate + */ +static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 60); +} + +/** + * @brief Get field lon from image_available message + * + * @return GPS Y coordinate + */ +static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 64); +} + +/** + * @brief Get field alt from image_available message + * + * @return Global frame altitude + */ +static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 68); +} + +/** + * @brief Get field ground_x from image_available message + * + * @return Ground truth X + */ +static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 72); +} + +/** + * @brief Get field ground_y from image_available message + * + * @return Ground truth Y + */ +static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 76); +} + +/** + * @brief Get field ground_z from image_available message + * + * @return Ground truth Z + */ +static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 80); +} + +/** + * @brief Decode a image_available message into a struct + * + * @param msg The message to decode + * @param image_available C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available) +{ +#if MAVLINK_NEED_BYTE_SWAP + image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); + image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); + image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); + image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); + image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); + image_available->key = mavlink_msg_image_available_get_key(msg); + image_available->exposure = mavlink_msg_image_available_get_exposure(msg); + image_available->gain = mavlink_msg_image_available_get_gain(msg); + image_available->roll = mavlink_msg_image_available_get_roll(msg); + image_available->pitch = mavlink_msg_image_available_get_pitch(msg); + image_available->yaw = mavlink_msg_image_available_get_yaw(msg); + image_available->local_z = mavlink_msg_image_available_get_local_z(msg); + image_available->lat = mavlink_msg_image_available_get_lat(msg); + image_available->lon = mavlink_msg_image_available_get_lon(msg); + image_available->alt = mavlink_msg_image_available_get_alt(msg); + image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg); + image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg); + image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg); + image_available->width = mavlink_msg_image_available_get_width(msg); + image_available->height = mavlink_msg_image_available_get_height(msg); + image_available->depth = mavlink_msg_image_available_get_depth(msg); + image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); + image_available->channels = mavlink_msg_image_available_get_channels(msg); +#else + memcpy(image_available, _MAV_PAYLOAD(msg), 92); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_trigger_control.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_trigger_control.h new file mode 100644 index 0000000000..08f4d7944d --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_trigger_control.h @@ -0,0 +1,144 @@ +// MESSAGE IMAGE_TRIGGER_CONTROL PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 153 + +typedef struct __mavlink_image_trigger_control_t +{ + uint8_t enable; ///< 0 to disable, 1 to enable +} mavlink_image_trigger_control_t; + +#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN 1 +#define MAVLINK_MSG_ID_153_LEN 1 + + + +#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL { \ + "IMAGE_TRIGGER_CONTROL", \ + 1, \ + { { "enable", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_image_trigger_control_t, enable) }, \ + } \ +} + + +/** + * @brief Pack a image_trigger_control message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param enable 0 to disable, 1 to enable + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t enable) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[1]; + _mav_put_uint8_t(buf, 0, enable); + + memcpy(_MAV_PAYLOAD(msg), buf, 1); +#else + mavlink_image_trigger_control_t packet; + packet.enable = enable; + + memcpy(_MAV_PAYLOAD(msg), &packet, 1); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; + return mavlink_finalize_message(msg, system_id, component_id, 1, 95); +} + +/** + * @brief Pack a image_trigger_control message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param enable 0 to disable, 1 to enable + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t enable) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[1]; + _mav_put_uint8_t(buf, 0, enable); + + memcpy(_MAV_PAYLOAD(msg), buf, 1); +#else + mavlink_image_trigger_control_t packet; + packet.enable = enable; + + memcpy(_MAV_PAYLOAD(msg), &packet, 1); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 1, 95); +} + +/** + * @brief Encode a image_trigger_control struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param image_trigger_control C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control) +{ + return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable); +} + +/** + * @brief Send a image_trigger_control message + * @param chan MAVLink channel to send the message + * + * @param enable 0 to disable, 1 to enable + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[1]; + _mav_put_uint8_t(buf, 0, enable); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, 1, 95); +#else + mavlink_image_trigger_control_t packet; + packet.enable = enable; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, 1, 95); +#endif +} + +#endif + +// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING + + +/** + * @brief Get field enable from image_trigger_control message + * + * @return 0 to disable, 1 to enable + */ +static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Decode a image_trigger_control message into a struct + * + * @param msg The message to decode + * @param image_trigger_control C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control) +{ +#if MAVLINK_NEED_BYTE_SWAP + image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg); +#else + memcpy(image_trigger_control, _MAV_PAYLOAD(msg), 1); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_triggered.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_triggered.h new file mode 100644 index 0000000000..d82abcf8ee --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_image_triggered.h @@ -0,0 +1,386 @@ +// MESSAGE IMAGE_TRIGGERED PACKING + +#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 152 + +typedef struct __mavlink_image_triggered_t +{ + uint64_t timestamp; ///< Timestamp + uint32_t seq; ///< IMU seq + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad + float local_z; ///< Local frame Z coordinate (height over ground) + float lat; ///< GPS X coordinate + float lon; ///< GPS Y coordinate + float alt; ///< Global frame altitude + float ground_x; ///< Ground truth X + float ground_y; ///< Ground truth Y + float ground_z; ///< Ground truth Z +} mavlink_image_triggered_t; + +#define MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN 52 +#define MAVLINK_MSG_ID_152_LEN 52 + + + +#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED { \ + "IMAGE_TRIGGERED", \ + 12, \ + { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_triggered_t, timestamp) }, \ + { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_image_triggered_t, seq) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_image_triggered_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_image_triggered_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_image_triggered_t, yaw) }, \ + { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_image_triggered_t, local_z) }, \ + { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_image_triggered_t, lat) }, \ + { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_image_triggered_t, lon) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_image_triggered_t, alt) }, \ + { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_triggered_t, ground_x) }, \ + { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_triggered_t, ground_y) }, \ + { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_triggered_t, ground_z) }, \ + } \ +} + + +/** + * @brief Pack a image_triggered message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[52]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_float(buf, 24, local_z); + _mav_put_float(buf, 28, lat); + _mav_put_float(buf, 32, lon); + _mav_put_float(buf, 36, alt); + _mav_put_float(buf, 40, ground_x); + _mav_put_float(buf, 44, ground_y); + _mav_put_float(buf, 48, ground_z); + + memcpy(_MAV_PAYLOAD(msg), buf, 52); +#else + mavlink_image_triggered_t packet; + packet.timestamp = timestamp; + packet.seq = seq; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 52); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; + return mavlink_finalize_message(msg, system_id, component_id, 52, 86); +} + +/** + * @brief Pack a image_triggered message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t timestamp,uint32_t seq,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[52]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_float(buf, 24, local_z); + _mav_put_float(buf, 28, lat); + _mav_put_float(buf, 32, lon); + _mav_put_float(buf, 36, alt); + _mav_put_float(buf, 40, ground_x); + _mav_put_float(buf, 44, ground_y); + _mav_put_float(buf, 48, ground_z); + + memcpy(_MAV_PAYLOAD(msg), buf, 52); +#else + mavlink_image_triggered_t packet; + packet.timestamp = timestamp; + packet.seq = seq; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 52); +#endif + + msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 52, 86); +} + +/** + * @brief Encode a image_triggered struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param image_triggered C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) +{ + return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z); +} + +/** + * @brief Send a image_triggered message + * @param chan MAVLink channel to send the message + * + * @param timestamp Timestamp + * @param seq IMU seq + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @param local_z Local frame Z coordinate (height over ground) + * @param lat GPS X coordinate + * @param lon GPS Y coordinate + * @param alt Global frame altitude + * @param ground_x Ground truth X + * @param ground_y Ground truth Y + * @param ground_z Ground truth Z + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[52]; + _mav_put_uint64_t(buf, 0, timestamp); + _mav_put_uint32_t(buf, 8, seq); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_float(buf, 24, local_z); + _mav_put_float(buf, 28, lat); + _mav_put_float(buf, 32, lon); + _mav_put_float(buf, 36, alt); + _mav_put_float(buf, 40, ground_x); + _mav_put_float(buf, 44, ground_y); + _mav_put_float(buf, 48, ground_z); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, 52, 86); +#else + mavlink_image_triggered_t packet; + packet.timestamp = timestamp; + packet.seq = seq; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.local_z = local_z; + packet.lat = lat; + packet.lon = lon; + packet.alt = alt; + packet.ground_x = ground_x; + packet.ground_y = ground_y; + packet.ground_z = ground_z; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, 52, 86); +#endif +} + +#endif + +// MESSAGE IMAGE_TRIGGERED UNPACKING + + +/** + * @brief Get field timestamp from image_triggered message + * + * @return Timestamp + */ +static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field seq from image_triggered message + * + * @return IMU seq + */ +static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 8); +} + +/** + * @brief Get field roll from image_triggered message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pitch from image_triggered message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field yaw from image_triggered message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field local_z from image_triggered message + * + * @return Local frame Z coordinate (height over ground) + */ +static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field lat from image_triggered message + * + * @return GPS X coordinate + */ +static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field lon from image_triggered message + * + * @return GPS Y coordinate + */ +static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field alt from image_triggered message + * + * @return Global frame altitude + */ +static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Get field ground_x from image_triggered message + * + * @return Ground truth X + */ +static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 40); +} + +/** + * @brief Get field ground_y from image_triggered message + * + * @return Ground truth Y + */ +static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 44); +} + +/** + * @brief Get field ground_z from image_triggered message + * + * @return Ground truth Z + */ +static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 48); +} + +/** + * @brief Decode a image_triggered message into a struct + * + * @param msg The message to decode + * @param image_triggered C-struct to decode the message contents into + */ +static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered) +{ +#if MAVLINK_NEED_BYTE_SWAP + image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg); + image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg); + image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg); + image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg); + image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg); + image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg); + image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg); + image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg); + image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg); + image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg); + image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg); + image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg); +#else + memcpy(image_triggered, _MAV_PAYLOAD(msg), 52); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_marker.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_marker.h new file mode 100644 index 0000000000..f127d56730 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_marker.h @@ -0,0 +1,276 @@ +// MESSAGE MARKER PACKING + +#define MAVLINK_MSG_ID_MARKER 171 + +typedef struct __mavlink_marker_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float roll; ///< roll orientation + float pitch; ///< pitch orientation + float yaw; ///< yaw orientation + uint16_t id; ///< ID +} mavlink_marker_t; + +#define MAVLINK_MSG_ID_MARKER_LEN 26 +#define MAVLINK_MSG_ID_171_LEN 26 + + + +#define MAVLINK_MESSAGE_INFO_MARKER { \ + "MARKER", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_marker_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_marker_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_marker_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_marker_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_marker_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_marker_t, yaw) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_marker_t, id) }, \ + } \ +} + + +/** + * @brief Pack a marker message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_marker_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.id = id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_MARKER; + return mavlink_finalize_message(msg, system_id, component_id, 26, 249); +} + +/** + * @brief Pack a marker message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); + + memcpy(_MAV_PAYLOAD(msg), buf, 26); +#else + mavlink_marker_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.id = id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 26); +#endif + + msg->msgid = MAVLINK_MSG_ID_MARKER; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 249); +} + +/** + * @brief Encode a marker struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param marker C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker) +{ + return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw); +} + +/** + * @brief Send a marker message + * @param chan MAVLink channel to send the message + * + * @param id ID + * @param x x position + * @param y y position + * @param z z position + * @param roll roll orientation + * @param pitch pitch orientation + * @param yaw yaw orientation + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[26]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, roll); + _mav_put_float(buf, 16, pitch); + _mav_put_float(buf, 20, yaw); + _mav_put_uint16_t(buf, 24, id); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, 26, 249); +#else + mavlink_marker_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.id = id; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, 26, 249); +#endif +} + +#endif + +// MESSAGE MARKER UNPACKING + + +/** + * @brief Get field id from marker message + * + * @return ID + */ +static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field x from marker message + * + * @return x position + */ +static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from marker message + * + * @return y position + */ +static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from marker message + * + * @return z position + */ +static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field roll from marker message + * + * @return roll orientation + */ +static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field pitch from marker message + * + * @return pitch orientation + */ +static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field yaw from marker message + * + * @return yaw orientation + */ +static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a marker message into a struct + * + * @param msg The message to decode + * @param marker C-struct to decode the message contents into + */ +static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker) +{ +#if MAVLINK_NEED_BYTE_SWAP + marker->x = mavlink_msg_marker_get_x(msg); + marker->y = mavlink_msg_marker_get_y(msg); + marker->z = mavlink_msg_marker_get_z(msg); + marker->roll = mavlink_msg_marker_get_roll(msg); + marker->pitch = mavlink_msg_marker_get_pitch(msg); + marker->yaw = mavlink_msg_marker_get_yaw(msg); + marker->id = mavlink_msg_marker_get_id(msg); +#else + memcpy(marker, _MAV_PAYLOAD(msg), 26); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_pattern_detected.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_pattern_detected.h new file mode 100644 index 0000000000..2bbc64681a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_pattern_detected.h @@ -0,0 +1,204 @@ +// MESSAGE PATTERN_DETECTED PACKING + +#define MAVLINK_MSG_ID_PATTERN_DETECTED 190 + +typedef struct __mavlink_pattern_detected_t +{ + float confidence; ///< Confidence of detection + uint8_t type; ///< 0: Pattern, 1: Letter + char file[100]; ///< Pattern file name + uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes +} mavlink_pattern_detected_t; + +#define MAVLINK_MSG_ID_PATTERN_DETECTED_LEN 106 +#define MAVLINK_MSG_ID_190_LEN 106 + +#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100 + +#define MAVLINK_MESSAGE_INFO_PATTERN_DETECTED { \ + "PATTERN_DETECTED", \ + 4, \ + { { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pattern_detected_t, confidence) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_pattern_detected_t, type) }, \ + { "file", NULL, MAVLINK_TYPE_CHAR, 100, 5, offsetof(mavlink_pattern_detected_t, file) }, \ + { "detected", NULL, MAVLINK_TYPE_UINT8_T, 0, 105, offsetof(mavlink_pattern_detected_t, detected) }, \ + } \ +} + + +/** + * @brief Pack a pattern_detected message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, float confidence, const char *file, uint8_t detected) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[106]; + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 105, detected); + _mav_put_char_array(buf, 5, file, 100); + memcpy(_MAV_PAYLOAD(msg), buf, 106); +#else + mavlink_pattern_detected_t packet; + packet.confidence = confidence; + packet.type = type; + packet.detected = detected; + memcpy(packet.file, file, sizeof(char)*100); + memcpy(_MAV_PAYLOAD(msg), &packet, 106); +#endif + + msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; + return mavlink_finalize_message(msg, system_id, component_id, 106, 90); +} + +/** + * @brief Pack a pattern_detected message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,float confidence,const char *file,uint8_t detected) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[106]; + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 105, detected); + _mav_put_char_array(buf, 5, file, 100); + memcpy(_MAV_PAYLOAD(msg), buf, 106); +#else + mavlink_pattern_detected_t packet; + packet.confidence = confidence; + packet.type = type; + packet.detected = detected; + memcpy(packet.file, file, sizeof(char)*100); + memcpy(_MAV_PAYLOAD(msg), &packet, 106); +#endif + + msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106, 90); +} + +/** + * @brief Encode a pattern_detected struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param pattern_detected C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected) +{ + return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected); +} + +/** + * @brief Send a pattern_detected message + * @param chan MAVLink channel to send the message + * + * @param type 0: Pattern, 1: Letter + * @param confidence Confidence of detection + * @param file Pattern file name + * @param detected Accepted as true detection, 0 no, 1 yes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[106]; + _mav_put_float(buf, 0, confidence); + _mav_put_uint8_t(buf, 4, type); + _mav_put_uint8_t(buf, 105, detected); + _mav_put_char_array(buf, 5, file, 100); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, 106, 90); +#else + mavlink_pattern_detected_t packet; + packet.confidence = confidence; + packet.type = type; + packet.detected = detected; + memcpy(packet.file, file, sizeof(char)*100); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, 106, 90); +#endif +} + +#endif + +// MESSAGE PATTERN_DETECTED UNPACKING + + +/** + * @brief Get field type from pattern_detected message + * + * @return 0: Pattern, 1: Letter + */ +static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field confidence from pattern_detected message + * + * @return Confidence of detection + */ +static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field file from pattern_detected message + * + * @return Pattern file name + */ +static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, char *file) +{ + return _MAV_RETURN_char_array(msg, file, 100, 5); +} + +/** + * @brief Get field detected from pattern_detected message + * + * @return Accepted as true detection, 0 no, 1 yes + */ +static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 105); +} + +/** + * @brief Decode a pattern_detected message into a struct + * + * @param msg The message to decode + * @param pattern_detected C-struct to decode the message contents into + */ +static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected) +{ +#if MAVLINK_NEED_BYTE_SWAP + pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg); + pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); + mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); + pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); +#else + memcpy(pattern_detected, _MAV_PAYLOAD(msg), 106); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest.h new file mode 100644 index 0000000000..2c14d2385a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest.h @@ -0,0 +1,292 @@ +// MESSAGE POINT_OF_INTEREST PACKING + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST 191 + +typedef struct __mavlink_point_of_interest_t +{ + float x; ///< X Position + float y; ///< Y Position + float z; ///< Z Position + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local + char name[26]; ///< POI name +} mavlink_point_of_interest_t; + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN 43 +#define MAVLINK_MSG_ID_191_LEN 43 + +#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 26 + +#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST { \ + "POINT_OF_INTEREST", \ + 8, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_t, z) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_point_of_interest_t, timeout) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_point_of_interest_t, type) }, \ + { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_point_of_interest_t, color) }, \ + { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_point_of_interest_t, coordinate_system) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 26, 17, offsetof(mavlink_point_of_interest_t, name) }, \ + } \ +} + + +/** + * @brief Pack a point_of_interest message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[43]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); + _mav_put_char_array(buf, 17, name, 26); + memcpy(_MAV_PAYLOAD(msg), buf, 43); +#else + mavlink_point_of_interest_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + memcpy(_MAV_PAYLOAD(msg), &packet, 43); +#endif + + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; + return mavlink_finalize_message(msg, system_id, component_id, 43, 95); +} + +/** + * @brief Pack a point_of_interest message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float x,float y,float z,const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[43]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); + _mav_put_char_array(buf, 17, name, 26); + memcpy(_MAV_PAYLOAD(msg), buf, 43); +#else + mavlink_point_of_interest_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + memcpy(_MAV_PAYLOAD(msg), &packet, 43); +#endif + + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 43, 95); +} + +/** + * @brief Encode a point_of_interest struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param point_of_interest C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest) +{ + return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name); +} + +/** + * @brief Send a point_of_interest message + * @param chan MAVLink channel to send the message + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param x X Position + * @param y Y Position + * @param z Z Position + * @param name POI name + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[43]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_uint16_t(buf, 12, timeout); + _mav_put_uint8_t(buf, 14, type); + _mav_put_uint8_t(buf, 15, color); + _mav_put_uint8_t(buf, 16, coordinate_system); + _mav_put_char_array(buf, 17, name, 26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, 43, 95); +#else + mavlink_point_of_interest_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, 43, 95); +#endif +} + +#endif + +// MESSAGE POINT_OF_INTEREST UNPACKING + + +/** + * @brief Get field type from point_of_interest message + * + * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + */ +static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 14); +} + +/** + * @brief Get field color from point_of_interest message + * + * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + */ +static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 15); +} + +/** + * @brief Get field coordinate_system from point_of_interest message + * + * @return 0: global, 1:local + */ +static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field timeout from point_of_interest message + * + * @return 0: no timeout, >1: timeout in seconds + */ +static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field x from point_of_interest message + * + * @return X Position + */ +static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from point_of_interest message + * + * @return Y Position + */ +static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from point_of_interest message + * + * @return Z Position + */ +static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field name from point_of_interest message + * + * @return POI name + */ +static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 26, 17); +} + +/** + * @brief Decode a point_of_interest message into a struct + * + * @param msg The message to decode + * @param point_of_interest C-struct to decode the message contents into + */ +static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest) +{ +#if MAVLINK_NEED_BYTE_SWAP + point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg); + point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg); + point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg); + point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg); + point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg); + point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg); + point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); + mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name); +#else + memcpy(point_of_interest, _MAV_PAYLOAD(msg), 43); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h new file mode 100644 index 0000000000..b2c89ede83 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h @@ -0,0 +1,358 @@ +// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 192 + +typedef struct __mavlink_point_of_interest_connection_t +{ + float xp1; ///< X1 Position + float yp1; ///< Y1 Position + float zp1; ///< Z1 Position + float xp2; ///< X2 Position + float yp2; ///< Y2 Position + float zp2; ///< Z2 Position + uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds + uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + uint8_t coordinate_system; ///< 0: global, 1:local + char name[26]; ///< POI connection name +} mavlink_point_of_interest_connection_t; + +#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN 55 +#define MAVLINK_MSG_ID_192_LEN 55 + +#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 26 + +#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION { \ + "POINT_OF_INTEREST_CONNECTION", \ + 11, \ + { { "xp1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_connection_t, xp1) }, \ + { "yp1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_connection_t, yp1) }, \ + { "zp1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_connection_t, zp1) }, \ + { "xp2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_point_of_interest_connection_t, xp2) }, \ + { "yp2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_point_of_interest_connection_t, yp2) }, \ + { "zp2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_point_of_interest_connection_t, zp2) }, \ + { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_point_of_interest_connection_t, timeout) }, \ + { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_point_of_interest_connection_t, type) }, \ + { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_point_of_interest_connection_t, color) }, \ + { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_point_of_interest_connection_t, coordinate_system) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 26, 29, offsetof(mavlink_point_of_interest_connection_t, name) }, \ + } \ +} + + +/** + * @brief Pack a point_of_interest_connection message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[55]; + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); + _mav_put_char_array(buf, 29, name, 26); + memcpy(_MAV_PAYLOAD(msg), buf, 55); +#else + mavlink_point_of_interest_connection_t packet; + packet.xp1 = xp1; + packet.yp1 = yp1; + packet.zp1 = zp1; + packet.xp2 = xp2; + packet.yp2 = yp2; + packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + memcpy(_MAV_PAYLOAD(msg), &packet, 55); +#endif + + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; + return mavlink_finalize_message(msg, system_id, component_id, 55, 36); +} + +/** + * @brief Pack a point_of_interest_connection message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float xp1,float yp1,float zp1,float xp2,float yp2,float zp2,const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[55]; + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); + _mav_put_char_array(buf, 29, name, 26); + memcpy(_MAV_PAYLOAD(msg), buf, 55); +#else + mavlink_point_of_interest_connection_t packet; + packet.xp1 = xp1; + packet.yp1 = yp1; + packet.zp1 = zp1; + packet.xp2 = xp2; + packet.yp2 = yp2; + packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + memcpy(_MAV_PAYLOAD(msg), &packet, 55); +#endif + + msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 55, 36); +} + +/** + * @brief Encode a point_of_interest_connection struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param point_of_interest_connection C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection) +{ + return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name); +} + +/** + * @brief Send a point_of_interest_connection message + * @param chan MAVLink channel to send the message + * + * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + * @param coordinate_system 0: global, 1:local + * @param timeout 0: no timeout, >1: timeout in seconds + * @param xp1 X1 Position + * @param yp1 Y1 Position + * @param zp1 Z1 Position + * @param xp2 X2 Position + * @param yp2 Y2 Position + * @param zp2 Z2 Position + * @param name POI connection name + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[55]; + _mav_put_float(buf, 0, xp1); + _mav_put_float(buf, 4, yp1); + _mav_put_float(buf, 8, zp1); + _mav_put_float(buf, 12, xp2); + _mav_put_float(buf, 16, yp2); + _mav_put_float(buf, 20, zp2); + _mav_put_uint16_t(buf, 24, timeout); + _mav_put_uint8_t(buf, 26, type); + _mav_put_uint8_t(buf, 27, color); + _mav_put_uint8_t(buf, 28, coordinate_system); + _mav_put_char_array(buf, 29, name, 26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, 55, 36); +#else + mavlink_point_of_interest_connection_t packet; + packet.xp1 = xp1; + packet.yp1 = yp1; + packet.zp1 = zp1; + packet.xp2 = xp2; + packet.yp2 = yp2; + packet.zp2 = zp2; + packet.timeout = timeout; + packet.type = type; + packet.color = color; + packet.coordinate_system = coordinate_system; + memcpy(packet.name, name, sizeof(char)*26); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, 55, 36); +#endif +} + +#endif + +// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING + + +/** + * @brief Get field type from point_of_interest_connection message + * + * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field color from point_of_interest_connection message + * + * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 27); +} + +/** + * @brief Get field coordinate_system from point_of_interest_connection message + * + * @return 0: global, 1:local + */ +static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field timeout from point_of_interest_connection message + * + * @return 0: no timeout, >1: timeout in seconds + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field xp1 from point_of_interest_connection message + * + * @return X1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field yp1 from point_of_interest_connection message + * + * @return Y1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field zp1 from point_of_interest_connection message + * + * @return Z1 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field xp2 from point_of_interest_connection message + * + * @return X2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field yp2 from point_of_interest_connection message + * + * @return Y2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field zp2 from point_of_interest_connection message + * + * @return Z2 Position + */ +static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field name from point_of_interest_connection message + * + * @return POI connection name + */ +static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 26, 29); +} + +/** + * @brief Decode a point_of_interest_connection message into a struct + * + * @param msg The message to decode + * @param point_of_interest_connection C-struct to decode the message contents into + */ +static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection) +{ +#if MAVLINK_NEED_BYTE_SWAP + point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg); + point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg); + point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg); + point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg); + point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg); + point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg); + point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg); + point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg); + point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg); + point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); + mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name); +#else + memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), 55); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_offset_set.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_offset_set.h new file mode 100644 index 0000000000..cdb178d0ca --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_offset_set.h @@ -0,0 +1,254 @@ +// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 160 + +typedef struct __mavlink_position_control_offset_set_t +{ + float x; ///< x position offset + float y; ///< y position offset + float z; ///< z position offset + float yaw; ///< yaw orientation offset in radians, 0 = NORTH + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_position_control_offset_set_t; + +#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET_LEN 18 +#define MAVLINK_MSG_ID_160_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET { \ + "POSITION_CONTROL_OFFSET_SET", \ + 6, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_control_offset_set_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_offset_set_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_offset_set_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_offset_set_t, yaw) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_position_control_offset_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_position_control_offset_set_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a position_control_offset_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_position_control_offset_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; + return mavlink_finalize_message(msg, system_id, component_id, 18, 244); +} + +/** + * @brief Pack a position_control_offset_set message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_offset_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_position_control_offset_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 244); +} + +/** + * @brief Encode a position_control_offset_set struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_control_offset_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set) +{ + return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw); +} + +/** + * @brief Send a position_control_offset_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param x x position offset + * @param y y position offset + * @param z z position offset + * @param yaw yaw orientation offset in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint8_t(buf, 16, target_system); + _mav_put_uint8_t(buf, 17, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, buf, 18, 244); +#else + mavlink_position_control_offset_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, (const char *)&packet, 18, 244); +#endif +} + +#endif + +// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING + + +/** + * @brief Get field target_system from position_control_offset_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 16); +} + +/** + * @brief Get field target_component from position_control_offset_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 17); +} + +/** + * @brief Get field x from position_control_offset_set message + * + * @return x position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from position_control_offset_set message + * + * @return y position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from position_control_offset_set message + * + * @return z position offset + */ +static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from position_control_offset_set message + * + * @return yaw orientation offset in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a position_control_offset_set message into a struct + * + * @param msg The message to decode + * @param position_control_offset_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg); + position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg); + position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg); + position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg); + position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg); + position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg); +#else + memcpy(position_control_offset_set, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint.h new file mode 100644 index 0000000000..c170fb2265 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint.h @@ -0,0 +1,232 @@ +// MESSAGE POSITION_CONTROL_SETPOINT PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 170 + +typedef struct __mavlink_position_control_setpoint_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + uint16_t id; ///< ID of waypoint, 0 for plain position +} mavlink_position_control_setpoint_t; + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN 18 +#define MAVLINK_MSG_ID_170_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT { \ + "POSITION_CONTROL_SETPOINT", \ + 5, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_control_setpoint_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_t, yaw) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_position_control_setpoint_t, id) }, \ + } \ +} + + +/** + * @brief Pack a position_control_setpoint message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t id, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_position_control_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; + return mavlink_finalize_message(msg, system_id, component_id, 18, 28); +} + +/** + * @brief Pack a position_control_setpoint message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t id,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_position_control_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 28); +} + +/** + * @brief Encode a position_control_setpoint struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_control_setpoint C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint) +{ + return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw); +} + +/** + * @brief Send a position_control_setpoint message + * @param chan MAVLink channel to send the message + * + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, 18, 28); +#else + mavlink_position_control_setpoint_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, 18, 28); +#endif +} + +#endif + +// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING + + +/** + * @brief Get field id from position_control_setpoint message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field x from position_control_setpoint message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from position_control_setpoint message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from position_control_setpoint message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from position_control_setpoint message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a position_control_setpoint message into a struct + * + * @param msg The message to decode + * @param position_control_setpoint C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); + position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); + position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); + position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); + position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); +#else + memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint_set.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint_set.h new file mode 100644 index 0000000000..e24b347151 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_position_control_setpoint_set.h @@ -0,0 +1,276 @@ +// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 159 + +typedef struct __mavlink_position_control_setpoint_set_t +{ + float x; ///< x position + float y; ///< y position + float z; ///< z position + float yaw; ///< yaw orientation in radians, 0 = NORTH + uint16_t id; ///< ID of waypoint, 0 for plain position + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_position_control_setpoint_set_t; + +#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET_LEN 20 +#define MAVLINK_MSG_ID_159_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET { \ + "POSITION_CONTROL_SETPOINT_SET", \ + 7, \ + { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_control_setpoint_set_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_set_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_set_t, z) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_set_t, yaw) }, \ + { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_position_control_setpoint_set_t, id) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_position_control_setpoint_set_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_position_control_setpoint_set_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a position_control_setpoint_set message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_position_control_setpoint_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; + return mavlink_finalize_message(msg, system_id, component_id, 20, 11); +} + +/** + * @brief Pack a position_control_setpoint_set message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system,uint8_t target_component,uint16_t id,float x,float y,float z,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_position_control_setpoint_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 11); +} + +/** + * @brief Encode a position_control_setpoint_set struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param position_control_setpoint_set C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ + return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw); +} + +/** + * @brief Send a position_control_setpoint_set message + * @param chan MAVLink channel to send the message + * + * @param target_system System ID + * @param target_component Component ID + * @param id ID of waypoint, 0 for plain position + * @param x x position + * @param y y position + * @param z z position + * @param yaw yaw orientation in radians, 0 = NORTH + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_float(buf, 0, x); + _mav_put_float(buf, 4, y); + _mav_put_float(buf, 8, z); + _mav_put_float(buf, 12, yaw); + _mav_put_uint16_t(buf, 16, id); + _mav_put_uint8_t(buf, 18, target_system); + _mav_put_uint8_t(buf, 19, target_component); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, buf, 20, 11); +#else + mavlink_position_control_setpoint_set_t packet; + packet.x = x; + packet.y = y; + packet.z = z; + packet.yaw = yaw; + packet.id = id; + packet.target_system = target_system; + packet.target_component = target_component; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, (const char *)&packet, 20, 11); +#endif +} + +#endif + +// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING + + +/** + * @brief Get field target_system from position_control_setpoint_set message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 18); +} + +/** + * @brief Get field target_component from position_control_setpoint_set message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 19); +} + +/** + * @brief Get field id from position_control_setpoint_set message + * + * @return ID of waypoint, 0 for plain position + */ +static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 16); +} + +/** + * @brief Get field x from position_control_setpoint_set message + * + * @return x position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field y from position_control_setpoint_set message + * + * @return y position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field z from position_control_setpoint_set message + * + * @return z position + */ +static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field yaw from position_control_setpoint_set message + * + * @return yaw orientation in radians, 0 = NORTH + */ +static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Decode a position_control_setpoint_set message into a struct + * + * @param msg The message to decode + * @param position_control_setpoint_set C-struct to decode the message contents into + */ +static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set) +{ +#if MAVLINK_NEED_BYTE_SWAP + position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg); + position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg); + position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg); + position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg); + position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg); + position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg); + position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg); +#else + memcpy(position_control_setpoint_set, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_raw_aux.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_raw_aux.h new file mode 100644 index 0000000000..0bbf4d6220 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_raw_aux.h @@ -0,0 +1,276 @@ +// MESSAGE RAW_AUX PACKING + +#define MAVLINK_MSG_ID_RAW_AUX 172 + +typedef struct __mavlink_raw_aux_t +{ + int32_t baro; ///< Barometric pressure (hecto Pascal) + uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6) + uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2) + uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1) + uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3) + uint16_t vbat; ///< Battery voltage + int16_t temp; ///< Temperature (degrees celcius) +} mavlink_raw_aux_t; + +#define MAVLINK_MSG_ID_RAW_AUX_LEN 16 +#define MAVLINK_MSG_ID_172_LEN 16 + + + +#define MAVLINK_MESSAGE_INFO_RAW_AUX { \ + "RAW_AUX", \ + 7, \ + { { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_raw_aux_t, baro) }, \ + { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc1) }, \ + { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc2) }, \ + { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, adc3) }, \ + { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_raw_aux_t, adc4) }, \ + { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_raw_aux_t, vbat) }, \ + { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_aux_t, temp) }, \ + } \ +} + + +/** + * @brief Pack a raw_aux message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_raw_aux_t packet; + packet.baro = baro; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.vbat = vbat; + packet.temp = temp; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_AUX; + return mavlink_finalize_message(msg, system_id, component_id, 16, 182); +} + +/** + * @brief Pack a raw_aux message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t vbat,int16_t temp,int32_t baro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); + + memcpy(_MAV_PAYLOAD(msg), buf, 16); +#else + mavlink_raw_aux_t packet; + packet.baro = baro; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.vbat = vbat; + packet.temp = temp; + + memcpy(_MAV_PAYLOAD(msg), &packet, 16); +#endif + + msg->msgid = MAVLINK_MSG_ID_RAW_AUX; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 182); +} + +/** + * @brief Encode a raw_aux struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param raw_aux C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux) +{ + return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro); +} + +/** + * @brief Send a raw_aux message + * @param chan MAVLink channel to send the message + * + * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) + * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) + * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) + * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) + * @param vbat Battery voltage + * @param temp Temperature (degrees celcius) + * @param baro Barometric pressure (hecto Pascal) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[16]; + _mav_put_int32_t(buf, 0, baro); + _mav_put_uint16_t(buf, 4, adc1); + _mav_put_uint16_t(buf, 6, adc2); + _mav_put_uint16_t(buf, 8, adc3); + _mav_put_uint16_t(buf, 10, adc4); + _mav_put_uint16_t(buf, 12, vbat); + _mav_put_int16_t(buf, 14, temp); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, 16, 182); +#else + mavlink_raw_aux_t packet; + packet.baro = baro; + packet.adc1 = adc1; + packet.adc2 = adc2; + packet.adc3 = adc3; + packet.adc4 = adc4; + packet.vbat = vbat; + packet.temp = temp; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, 16, 182); +#endif +} + +#endif + +// MESSAGE RAW_AUX UNPACKING + + +/** + * @brief Get field adc1 from raw_aux message + * + * @return ADC1 (J405 ADC3, LPC2148 AD0.6) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field adc2 from raw_aux message + * + * @return ADC2 (J405 ADC5, LPC2148 AD0.2) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field adc3 from raw_aux message + * + * @return ADC3 (J405 ADC6, LPC2148 AD0.1) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Get field adc4 from raw_aux message + * + * @return ADC4 (J405 ADC7, LPC2148 AD1.3) + */ +static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 10); +} + +/** + * @brief Get field vbat from raw_aux message + * + * @return Battery voltage + */ +static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 12); +} + +/** + * @brief Get field temp from raw_aux message + * + * @return Temperature (degrees celcius) + */ +static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field baro from raw_aux message + * + * @return Barometric pressure (hecto Pascal) + */ +static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Decode a raw_aux message into a struct + * + * @param msg The message to decode + * @param raw_aux C-struct to decode the message contents into + */ +static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux) +{ +#if MAVLINK_NEED_BYTE_SWAP + raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); + raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg); + raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg); + raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg); + raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg); + raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); + raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); +#else + memcpy(raw_aux, _MAV_PAYLOAD(msg), 16); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_set_cam_shutter.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_set_cam_shutter.h new file mode 100644 index 0000000000..d72dc56975 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_set_cam_shutter.h @@ -0,0 +1,254 @@ +// MESSAGE SET_CAM_SHUTTER PACKING + +#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 151 + +typedef struct __mavlink_set_cam_shutter_t +{ + float gain; ///< Camera gain + uint16_t interval; ///< Shutter interval, in microseconds + uint16_t exposure; ///< Exposure time, in microseconds + uint8_t cam_no; ///< Camera id + uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual + uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly +} mavlink_set_cam_shutter_t; + +#define MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN 11 +#define MAVLINK_MSG_ID_151_LEN 11 + + + +#define MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER { \ + "SET_CAM_SHUTTER", \ + 6, \ + { { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_cam_shutter_t, gain) }, \ + { "interval", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_cam_shutter_t, interval) }, \ + { "exposure", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_cam_shutter_t, exposure) }, \ + { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_cam_shutter_t, cam_no) }, \ + { "cam_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_set_cam_shutter_t, cam_mode) }, \ + { "trigger_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_set_cam_shutter_t, trigger_pin) }, \ + } \ +} + + +/** + * @brief Pack a set_cam_shutter message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[11]; + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + memcpy(_MAV_PAYLOAD(msg), buf, 11); +#else + mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; + packet.cam_no = cam_no; + packet.cam_mode = cam_mode; + packet.trigger_pin = trigger_pin; + + memcpy(_MAV_PAYLOAD(msg), &packet, 11); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; + return mavlink_finalize_message(msg, system_id, component_id, 11, 108); +} + +/** + * @brief Pack a set_cam_shutter message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t cam_no,uint8_t cam_mode,uint8_t trigger_pin,uint16_t interval,uint16_t exposure,float gain) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[11]; + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + memcpy(_MAV_PAYLOAD(msg), buf, 11); +#else + mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; + packet.cam_no = cam_no; + packet.cam_mode = cam_mode; + packet.trigger_pin = trigger_pin; + + memcpy(_MAV_PAYLOAD(msg), &packet, 11); +#endif + + msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11, 108); +} + +/** + * @brief Encode a set_cam_shutter struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param set_cam_shutter C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter) +{ + return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain); +} + +/** + * @brief Send a set_cam_shutter message + * @param chan MAVLink channel to send the message + * + * @param cam_no Camera id + * @param cam_mode Camera mode: 0 = auto, 1 = manual + * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly + * @param interval Shutter interval, in microseconds + * @param exposure Exposure time, in microseconds + * @param gain Camera gain + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[11]; + _mav_put_float(buf, 0, gain); + _mav_put_uint16_t(buf, 4, interval); + _mav_put_uint16_t(buf, 6, exposure); + _mav_put_uint8_t(buf, 8, cam_no); + _mav_put_uint8_t(buf, 9, cam_mode); + _mav_put_uint8_t(buf, 10, trigger_pin); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, 11, 108); +#else + mavlink_set_cam_shutter_t packet; + packet.gain = gain; + packet.interval = interval; + packet.exposure = exposure; + packet.cam_no = cam_no; + packet.cam_mode = cam_mode; + packet.trigger_pin = trigger_pin; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, 11, 108); +#endif +} + +#endif + +// MESSAGE SET_CAM_SHUTTER UNPACKING + + +/** + * @brief Get field cam_no from set_cam_shutter message + * + * @return Camera id + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 8); +} + +/** + * @brief Get field cam_mode from set_cam_shutter message + * + * @return Camera mode: 0 = auto, 1 = manual + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 9); +} + +/** + * @brief Get field trigger_pin from set_cam_shutter message + * + * @return Trigger pin, 0-3 for PtGrey FireFly + */ +static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field interval from set_cam_shutter message + * + * @return Shutter interval, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field exposure from set_cam_shutter message + * + * @return Exposure time, in microseconds + */ +static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field gain from set_cam_shutter message + * + * @return Camera gain + */ +static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Decode a set_cam_shutter message into a struct + * + * @param msg The message to decode + * @param set_cam_shutter C-struct to decode the message contents into + */ +static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter) +{ +#if MAVLINK_NEED_BYTE_SWAP + set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); + set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); + set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); + set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg); + set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); + set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); +#else + memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), 11); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vicon_position_estimate.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vicon_position_estimate.h new file mode 100644 index 0000000000..40da2274d8 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vicon_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE VICON_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 157 + +typedef struct __mavlink_vicon_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_vicon_position_estimate_t; + +#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_157_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ + "VICON_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vicon_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 56); +} + +/** + * @brief Pack a vicon_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 56); +} + +/** + * @brief Encode a vicon_position_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vicon_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ + return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); +} + +/** + * @brief Send a vicon_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32, 56); +#else + mavlink_vicon_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32, 56); +#endif +} + +#endif + +// MESSAGE VICON_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vicon_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vicon_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vicon_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vicon_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vicon_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vicon_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vicon_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vicon_position_estimate message into a struct + * + * @param msg The message to decode + * @param vicon_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); + vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); + vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); + vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); + vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); + vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); + vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); +#else + memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_position_estimate.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_position_estimate.h new file mode 100644 index 0000000000..df39cbbfb1 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_position_estimate.h @@ -0,0 +1,276 @@ +// MESSAGE VISION_POSITION_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 156 + +typedef struct __mavlink_vision_position_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X position + float y; ///< Global Y position + float z; ///< Global Z position + float roll; ///< Roll angle in rad + float pitch; ///< Pitch angle in rad + float yaw; ///< Yaw angle in rad +} mavlink_vision_position_estimate_t; + +#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 +#define MAVLINK_MSG_ID_156_LEN 32 + + + +#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ + "VISION_POSITION_ESTIMATE", \ + 7, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ + } \ +} + + +/** + * @brief Pack a vision_position_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 32, 158); +} + +/** + * @brief Pack a vision_position_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 158); +} + +/** + * @brief Encode a vision_position_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_position_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) +{ + return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); +} + +/** + * @brief Send a vision_position_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X position + * @param y Global Y position + * @param z Global Z position + * @param roll Roll angle in rad + * @param pitch Pitch angle in rad + * @param yaw Yaw angle in rad + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32, 158); +#else + mavlink_vision_position_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 158); +#endif +} + +#endif + +// MESSAGE VISION_POSITION_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_position_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_position_estimate message + * + * @return Global X position + */ +static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_position_estimate message + * + * @return Global Y position + */ +static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_position_estimate message + * + * @return Global Z position + */ +static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from vision_position_estimate message + * + * @return Roll angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from vision_position_estimate message + * + * @return Pitch angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from vision_position_estimate message + * + * @return Yaw angle in rad + */ +static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a vision_position_estimate message into a struct + * + * @param msg The message to decode + * @param vision_position_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); + vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); + vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); + vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); + vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); + vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); + vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); +#else + memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_speed_estimate.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_speed_estimate.h new file mode 100644 index 0000000000..500947d6f4 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_vision_speed_estimate.h @@ -0,0 +1,210 @@ +// MESSAGE VISION_SPEED_ESTIMATE PACKING + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 158 + +typedef struct __mavlink_vision_speed_estimate_t +{ + uint64_t usec; ///< Timestamp (milliseconds) + float x; ///< Global X speed + float y; ///< Global Y speed + float z; ///< Global Z speed +} mavlink_vision_speed_estimate_t; + +#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 +#define MAVLINK_MSG_ID_158_LEN 20 + + + +#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ + "VISION_SPEED_ESTIMATE", \ + 4, \ + { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ + } \ +} + + +/** + * @brief Pack a vision_speed_estimate message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + return mavlink_finalize_message(msg, system_id, component_id, 20, 208); +} + +/** + * @brief Pack a vision_speed_estimate message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float x,float y,float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + memcpy(_MAV_PAYLOAD(msg), buf, 20); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + memcpy(_MAV_PAYLOAD(msg), &packet, 20); +#endif + + msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 208); +} + +/** + * @brief Encode a vision_speed_estimate struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param vision_speed_estimate C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ + return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); +} + +/** + * @brief Send a vision_speed_estimate message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (milliseconds) + * @param x Global X speed + * @param y Global Y speed + * @param z Global Z speed + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[20]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, x); + _mav_put_float(buf, 12, y); + _mav_put_float(buf, 16, z); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20, 208); +#else + mavlink_vision_speed_estimate_t packet; + packet.usec = usec; + packet.x = x; + packet.y = y; + packet.z = z; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20, 208); +#endif +} + +#endif + +// MESSAGE VISION_SPEED_ESTIMATE UNPACKING + + +/** + * @brief Get field usec from vision_speed_estimate message + * + * @return Timestamp (milliseconds) + */ +static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field x from vision_speed_estimate message + * + * @return Global X speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field y from vision_speed_estimate message + * + * @return Global Y speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field z from vision_speed_estimate message + * + * @return Global Z speed + */ +static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Decode a vision_speed_estimate message into a struct + * + * @param msg The message to decode + * @param vision_speed_estimate C-struct to decode the message contents into + */ +static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) +{ +#if MAVLINK_NEED_BYTE_SWAP + vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); + vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); + vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); + vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); +#else + memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), 20); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_command.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_command.h new file mode 100644 index 0000000000..1936f00515 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_command.h @@ -0,0 +1,210 @@ +// MESSAGE WATCHDOG_COMMAND PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 183 + +typedef struct __mavlink_watchdog_command_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint8_t target_system_id; ///< Target system ID + uint8_t command_id; ///< Command ID +} mavlink_watchdog_command_t; + +#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN 6 +#define MAVLINK_MSG_ID_183_LEN 6 + + + +#define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \ + "WATCHDOG_COMMAND", \ + 4, \ + { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_command_t, process_id) }, \ + { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_command_t, target_system_id) }, \ + { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_command_t, command_id) }, \ + } \ +} + + +/** + * @brief Pack a watchdog_command message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target_system_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); + _mav_put_uint8_t(buf, 5, command_id); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_watchdog_command_t packet; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.target_system_id = target_system_id; + packet.command_id = command_id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; + return mavlink_finalize_message(msg, system_id, component_id, 6, 162); +} + +/** + * @brief Pack a watchdog_command message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target_system_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target_system_id,uint16_t watchdog_id,uint16_t process_id,uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); + _mav_put_uint8_t(buf, 5, command_id); + + memcpy(_MAV_PAYLOAD(msg), buf, 6); +#else + mavlink_watchdog_command_t packet; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.target_system_id = target_system_id; + packet.command_id = command_id; + + memcpy(_MAV_PAYLOAD(msg), &packet, 6); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 162); +} + +/** + * @brief Encode a watchdog_command struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param watchdog_command C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) +{ + return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); +} + +/** + * @brief Send a watchdog_command message + * @param chan MAVLink channel to send the message + * + * @param target_system_id Target system ID + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param command_id Command ID + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[6]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_id); + _mav_put_uint8_t(buf, 4, target_system_id); + _mav_put_uint8_t(buf, 5, command_id); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6, 162); +#else + mavlink_watchdog_command_t packet; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.target_system_id = target_system_id; + packet.command_id = command_id; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6, 162); +#endif +} + +#endif + +// MESSAGE WATCHDOG_COMMAND UNPACKING + + +/** + * @brief Get field target_system_id from watchdog_command message + * + * @return Target system ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field watchdog_id from watchdog_command message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field process_id from watchdog_command message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Get field command_id from watchdog_command message + * + * @return Command ID + */ +static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Decode a watchdog_command message into a struct + * + * @param msg The message to decode + * @param watchdog_command C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) +{ +#if MAVLINK_NEED_BYTE_SWAP + watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); + watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); + watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); + watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); +#else + memcpy(watchdog_command, _MAV_PAYLOAD(msg), 6); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h new file mode 100644 index 0000000000..6c3dc333d2 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h @@ -0,0 +1,166 @@ +// MESSAGE WATCHDOG_HEARTBEAT PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 180 + +typedef struct __mavlink_watchdog_heartbeat_t +{ + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_count; ///< Number of processes +} mavlink_watchdog_heartbeat_t; + +#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN 4 +#define MAVLINK_MSG_ID_180_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT { \ + "WATCHDOG_HEARTBEAT", \ + 2, \ + { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_heartbeat_t, watchdog_id) }, \ + { "process_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_heartbeat_t, process_count) }, \ + } \ +} + + +/** + * @brief Pack a watchdog_heartbeat message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t watchdog_id, uint16_t process_count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_count); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_watchdog_heartbeat_t packet; + packet.watchdog_id = watchdog_id; + packet.process_count = process_count; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; + return mavlink_finalize_message(msg, system_id, component_id, 4, 153); +} + +/** + * @brief Pack a watchdog_heartbeat message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t watchdog_id,uint16_t process_count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_count); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_watchdog_heartbeat_t packet; + packet.watchdog_id = watchdog_id; + packet.process_count = process_count; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 153); +} + +/** + * @brief Encode a watchdog_heartbeat struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param watchdog_heartbeat C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ + return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count); +} + +/** + * @brief Send a watchdog_heartbeat message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_count Number of processes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, watchdog_id); + _mav_put_uint16_t(buf, 2, process_count); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, 4, 153); +#else + mavlink_watchdog_heartbeat_t packet; + packet.watchdog_id = watchdog_id; + packet.process_count = process_count; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, 4, 153); +#endif +} + +#endif + +// MESSAGE WATCHDOG_HEARTBEAT UNPACKING + + +/** + * @brief Get field watchdog_id from watchdog_heartbeat message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Get field process_count from watchdog_heartbeat message + * + * @return Number of processes + */ +static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 2); +} + +/** + * @brief Decode a watchdog_heartbeat message into a struct + * + * @param msg The message to decode + * @param watchdog_heartbeat C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat) +{ +#if MAVLINK_NEED_BYTE_SWAP + watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg); + watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg); +#else + memcpy(watchdog_heartbeat, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_info.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_info.h new file mode 100644 index 0000000000..59b0d3048c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_info.h @@ -0,0 +1,227 @@ +// MESSAGE WATCHDOG_PROCESS_INFO PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 181 + +typedef struct __mavlink_watchdog_process_info_t +{ + int32_t timeout; ///< Timeout (seconds) + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + char name[100]; ///< Process name + char arguments[147]; ///< Process arguments +} mavlink_watchdog_process_info_t; + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN 255 +#define MAVLINK_MSG_ID_181_LEN 255 + +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100 +#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147 + +#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO { \ + "WATCHDOG_PROCESS_INFO", \ + 5, \ + { { "timeout", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_info_t, timeout) }, \ + { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_info_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_info_t, process_id) }, \ + { "name", NULL, MAVLINK_TYPE_CHAR, 100, 8, offsetof(mavlink_watchdog_process_info_t, name) }, \ + { "arguments", NULL, MAVLINK_TYPE_CHAR, 147, 108, offsetof(mavlink_watchdog_process_info_t, arguments) }, \ + } \ +} + + +/** + * @brief Pack a watchdog_process_info message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + memcpy(_MAV_PAYLOAD(msg), buf, 255); +#else + mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + memcpy(packet.name, name, sizeof(char)*100); + memcpy(packet.arguments, arguments, sizeof(char)*147); + memcpy(_MAV_PAYLOAD(msg), &packet, 255); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; + return mavlink_finalize_message(msg, system_id, component_id, 255, 16); +} + +/** + * @brief Pack a watchdog_process_info message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t watchdog_id,uint16_t process_id,const char *name,const char *arguments,int32_t timeout) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + memcpy(_MAV_PAYLOAD(msg), buf, 255); +#else + mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + memcpy(packet.name, name, sizeof(char)*100); + memcpy(packet.arguments, arguments, sizeof(char)*147); + memcpy(_MAV_PAYLOAD(msg), &packet, 255); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255, 16); +} + +/** + * @brief Encode a watchdog_process_info struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param watchdog_process_info C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info) +{ + return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout); +} + +/** + * @brief Send a watchdog_process_info message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param name Process name + * @param arguments Process arguments + * @param timeout Timeout (seconds) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[255]; + _mav_put_int32_t(buf, 0, timeout); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_char_array(buf, 8, name, 100); + _mav_put_char_array(buf, 108, arguments, 147); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, 255, 16); +#else + mavlink_watchdog_process_info_t packet; + packet.timeout = timeout; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + memcpy(packet.name, name, sizeof(char)*100); + memcpy(packet.arguments, arguments, sizeof(char)*147); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, 255, 16); +#endif +} + +#endif + +// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING + + +/** + * @brief Get field watchdog_id from watchdog_process_info message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field process_id from watchdog_process_info message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field name from watchdog_process_info message + * + * @return Process name + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, char *name) +{ + return _MAV_RETURN_char_array(msg, name, 100, 8); +} + +/** + * @brief Get field arguments from watchdog_process_info message + * + * @return Process arguments + */ +static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, char *arguments) +{ + return _MAV_RETURN_char_array(msg, arguments, 147, 108); +} + +/** + * @brief Get field timeout from watchdog_process_info message + * + * @return Timeout (seconds) + */ +static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Decode a watchdog_process_info message into a struct + * + * @param msg The message to decode + * @param watchdog_process_info C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info) +{ +#if MAVLINK_NEED_BYTE_SWAP + watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); + watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg); + watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg); + mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); + mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); +#else + memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), 255); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_status.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_status.h new file mode 100644 index 0000000000..6fb26e5735 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/mavlink_msg_watchdog_process_status.h @@ -0,0 +1,254 @@ +// MESSAGE WATCHDOG_PROCESS_STATUS PACKING + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 182 + +typedef struct __mavlink_watchdog_process_status_t +{ + int32_t pid; ///< PID + uint16_t watchdog_id; ///< Watchdog ID + uint16_t process_id; ///< Process ID + uint16_t crashes; ///< Number of crashes + uint8_t state; ///< Is running / finished / suspended / crashed + uint8_t muted; ///< Is muted +} mavlink_watchdog_process_status_t; + +#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12 +#define MAVLINK_MSG_ID_182_LEN 12 + + + +#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \ + "WATCHDOG_PROCESS_STATUS", \ + 6, \ + { { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, pid) }, \ + { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \ + { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, process_id) }, \ + { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_watchdog_process_status_t, crashes) }, \ + { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, state) }, \ + { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_watchdog_process_status_t, muted) }, \ + } \ +} + + +/** + * @brief Pack a watchdog_process_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_watchdog_process_status_t packet; + packet.pid = pid; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.crashes = crashes; + packet.state = state; + packet.muted = muted; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 12, 29); +} + +/** + * @brief Pack a watchdog_process_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint16_t watchdog_id,uint16_t process_id,uint8_t state,uint8_t muted,int32_t pid,uint16_t crashes) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + memcpy(_MAV_PAYLOAD(msg), buf, 12); +#else + mavlink_watchdog_process_status_t packet; + packet.pid = pid; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.crashes = crashes; + packet.state = state; + packet.muted = muted; + + memcpy(_MAV_PAYLOAD(msg), &packet, 12); +#endif + + msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 29); +} + +/** + * @brief Encode a watchdog_process_status struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param watchdog_process_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status) +{ + return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes); +} + +/** + * @brief Send a watchdog_process_status message + * @param chan MAVLink channel to send the message + * + * @param watchdog_id Watchdog ID + * @param process_id Process ID + * @param state Is running / finished / suspended / crashed + * @param muted Is muted + * @param pid PID + * @param crashes Number of crashes + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[12]; + _mav_put_int32_t(buf, 0, pid); + _mav_put_uint16_t(buf, 4, watchdog_id); + _mav_put_uint16_t(buf, 6, process_id); + _mav_put_uint16_t(buf, 8, crashes); + _mav_put_uint8_t(buf, 10, state); + _mav_put_uint8_t(buf, 11, muted); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, 12, 29); +#else + mavlink_watchdog_process_status_t packet; + packet.pid = pid; + packet.watchdog_id = watchdog_id; + packet.process_id = process_id; + packet.crashes = crashes; + packet.state = state; + packet.muted = muted; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, 12, 29); +#endif +} + +#endif + +// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING + + +/** + * @brief Get field watchdog_id from watchdog_process_status message + * + * @return Watchdog ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 4); +} + +/** + * @brief Get field process_id from watchdog_process_status message + * + * @return Process ID + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 6); +} + +/** + * @brief Get field state from watchdog_process_status message + * + * @return Is running / finished / suspended / crashed + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 10); +} + +/** + * @brief Get field muted from watchdog_process_status message + * + * @return Is muted + */ +static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 11); +} + +/** + * @brief Get field pid from watchdog_process_status message + * + * @return PID + */ +static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 0); +} + +/** + * @brief Get field crashes from watchdog_process_status message + * + * @return Number of crashes + */ +static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Decode a watchdog_process_status message into a struct + * + * @param msg The message to decode + * @param watchdog_process_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); + watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg); + watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg); + watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); + watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); + watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); +#else + memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), 12); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/pixhawk.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/pixhawk.h new file mode 100644 index 0000000000..51b2eb2b60 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/pixhawk.h @@ -0,0 +1,80 @@ +/** @file + * @brief MAVLink comm protocol generated from pixhawk.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef PIXHAWK_H +#define PIXHAWK_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 0, 0, 0, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 8, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 108, 86, 95, 224, 0, 0, 0, 0, 11, 244, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 148, 223, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_PIXHAWK + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + +/** @brief Content Types for data transmission handshake */ +enum DATA_TYPES +{ + DATA_TYPE_JPEG_IMAGE=1, /* | */ + DATA_TYPE_RAW_IMAGE=2, /* | */ + DATA_TYPE_KINECT=3, /* | */ + DATA_TYPES_ENUM_END=4, /* | */ +}; + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_set_cam_shutter.h" +#include "./mavlink_msg_image_triggered.h" +#include "./mavlink_msg_image_trigger_control.h" +#include "./mavlink_msg_image_available.h" +#include "./mavlink_msg_position_control_setpoint_set.h" +#include "./mavlink_msg_position_control_offset_set.h" +#include "./mavlink_msg_position_control_setpoint.h" +#include "./mavlink_msg_marker.h" +#include "./mavlink_msg_raw_aux.h" +#include "./mavlink_msg_watchdog_heartbeat.h" +#include "./mavlink_msg_watchdog_process_info.h" +#include "./mavlink_msg_watchdog_process_status.h" +#include "./mavlink_msg_watchdog_command.h" +#include "./mavlink_msg_pattern_detected.h" +#include "./mavlink_msg_point_of_interest.h" +#include "./mavlink_msg_point_of_interest_connection.h" +#include "./mavlink_msg_data_transmission_handshake.h" +#include "./mavlink_msg_encapsulated_data.h" +#include "./mavlink_msg_brief_feature.h" +#include "./mavlink_msg_attitude_control.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // PIXHAWK_H diff --git a/libraries/GCS_MAVLink/include_v1.0/pixhawk/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/pixhawk/testsuite.h new file mode 100644 index 0000000000..ef2f0273b7 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/pixhawk/testsuite.h @@ -0,0 +1,1150 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from pixhawk.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef PIXHAWK_TESTSUITE_H +#define PIXHAWK_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_pixhawk(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_pixhawk(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_set_cam_shutter(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_set_cam_shutter_t packet_in = { + 17.0, + 17443, + 17547, + 29, + 96, + 163, + }; + mavlink_set_cam_shutter_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.gain = packet_in.gain; + packet1.interval = packet_in.interval; + packet1.exposure = packet_in.exposure; + packet1.cam_no = packet_in.cam_no; + packet1.cam_mode = packet_in.cam_mode; + packet1.trigger_pin = packet_in.trigger_pin; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_cam_shutter_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_set_cam_shutter_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_cam_shutter_pack(system_id, component_id, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain ); + mavlink_msg_set_cam_shutter_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_set_cam_shutter_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain ); + mavlink_msg_set_cam_shutter_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; ilen + MAVLINK_NUM_NON_PAYLOAD_BYTES; +} + +#if MAVLINK_NEED_BYTE_SWAP +static inline void byte_swap_2(char *dst, const char *src) +{ + dst[0] = src[1]; + dst[1] = src[0]; +} +static inline void byte_swap_4(char *dst, const char *src) +{ + dst[0] = src[3]; + dst[1] = src[2]; + dst[2] = src[1]; + dst[3] = src[0]; +} +static inline void byte_swap_8(char *dst, const char *src) +{ + dst[0] = src[7]; + dst[1] = src[6]; + dst[2] = src[5]; + dst[3] = src[4]; + dst[4] = src[3]; + dst[5] = src[2]; + dst[6] = src[1]; + dst[7] = src[0]; +} +#elif !MAVLINK_ALIGNED_FIELDS +static inline void byte_copy_2(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; +} +static inline void byte_copy_4(char *dst, const char *src) +{ + dst[0] = src[0]; + dst[1] = src[1]; + dst[2] = src[2]; + dst[3] = src[3]; +} +static inline void byte_copy_8(char *dst, const char *src) +{ + memcpy(dst, src, 8); +} +#endif + +#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b +#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b +#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b + +#if MAVLINK_NEED_BYTE_SWAP +#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) +#elif !MAVLINK_ALIGNED_FIELDS +#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) +#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) +#else +#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b +#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b +#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b +#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b +#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b +#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b +#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b +#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b +#endif + + +/* + * Place a char array into a buffer + */ +static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) +{ + if (b == NULL) { + memset(&buf[wire_offset], 0, array_length); + } else { + memcpy(&buf[wire_offset], b, array_length); + } +} + +/* + * Place a uint8_t array into a buffer + */ +static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) +{ + if (b == NULL) { + memset(&buf[wire_offset], 0, array_length); + } else { + memcpy(&buf[wire_offset], b, array_length); + } +} + +/* + * Place a int8_t array into a buffer + */ +static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) +{ + if (b == NULL) { + memset(&buf[wire_offset], 0, array_length); + } else { + memcpy(&buf[wire_offset], b, array_length); + } +} + +#if MAVLINK_NEED_BYTE_SWAP +#define _MAV_PUT_ARRAY(TYPE, V) \ +static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ +{ \ + if (b == NULL) { \ + memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ + } else { \ + uint16_t i; \ + for (i=0; imsgid = MAVLINK_MSG_ID_AIR_DATA; + return mavlink_finalize_message(msg, system_id, component_id, 10, 232); +} + +/** + * @brief Pack a air_data message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param dynamicPressure Dynamic pressure (Pa) + * @param staticPressure Static pressure (Pa) + * @param temperature Board temperature + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_air_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float dynamicPressure,float staticPressure,uint16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[10]; + _mav_put_float(buf, 0, dynamicPressure); + _mav_put_float(buf, 4, staticPressure); + _mav_put_uint16_t(buf, 8, temperature); + + memcpy(_MAV_PAYLOAD(msg), buf, 10); +#else + mavlink_air_data_t packet; + packet.dynamicPressure = dynamicPressure; + packet.staticPressure = staticPressure; + packet.temperature = temperature; + + memcpy(_MAV_PAYLOAD(msg), &packet, 10); +#endif + + msg->msgid = MAVLINK_MSG_ID_AIR_DATA; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10, 232); +} + +/** + * @brief Encode a air_data struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param air_data C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_air_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_air_data_t* air_data) +{ + return mavlink_msg_air_data_pack(system_id, component_id, msg, air_data->dynamicPressure, air_data->staticPressure, air_data->temperature); +} + +/** + * @brief Send a air_data message + * @param chan MAVLink channel to send the message + * + * @param dynamicPressure Dynamic pressure (Pa) + * @param staticPressure Static pressure (Pa) + * @param temperature Board temperature + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_air_data_send(mavlink_channel_t chan, float dynamicPressure, float staticPressure, uint16_t temperature) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[10]; + _mav_put_float(buf, 0, dynamicPressure); + _mav_put_float(buf, 4, staticPressure); + _mav_put_uint16_t(buf, 8, temperature); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIR_DATA, buf, 10, 232); +#else + mavlink_air_data_t packet; + packet.dynamicPressure = dynamicPressure; + packet.staticPressure = staticPressure; + packet.temperature = temperature; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIR_DATA, (const char *)&packet, 10, 232); +#endif +} + +#endif + +// MESSAGE AIR_DATA UNPACKING + + +/** + * @brief Get field dynamicPressure from air_data message + * + * @return Dynamic pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_dynamicPressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field staticPressure from air_data message + * + * @return Static pressure (Pa) + */ +static inline float mavlink_msg_air_data_get_staticPressure(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field temperature from air_data message + * + * @return Board temperature + */ +static inline uint16_t mavlink_msg_air_data_get_temperature(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 8); +} + +/** + * @brief Decode a air_data message into a struct + * + * @param msg The message to decode + * @param air_data C-struct to decode the message contents into + */ +static inline void mavlink_msg_air_data_decode(const mavlink_message_t* msg, mavlink_air_data_t* air_data) +{ +#if MAVLINK_NEED_BYTE_SWAP + air_data->dynamicPressure = mavlink_msg_air_data_get_dynamicPressure(msg); + air_data->staticPressure = mavlink_msg_air_data_get_staticPressure(msg); + air_data->temperature = mavlink_msg_air_data_get_temperature(msg); +#else + memcpy(air_data, _MAV_PAYLOAD(msg), 10); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_cpu_load.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_cpu_load.h new file mode 100644 index 0000000000..af9e03d37b --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_cpu_load.h @@ -0,0 +1,188 @@ +// MESSAGE CPU_LOAD PACKING + +#define MAVLINK_MSG_ID_CPU_LOAD 170 + +typedef struct __mavlink_cpu_load_t +{ + uint16_t batVolt; ///< Battery Voltage in millivolts + uint8_t sensLoad; ///< Sensor DSC Load + uint8_t ctrlLoad; ///< Control DSC Load +} mavlink_cpu_load_t; + +#define MAVLINK_MSG_ID_CPU_LOAD_LEN 4 +#define MAVLINK_MSG_ID_170_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_CPU_LOAD { \ + "CPU_LOAD", \ + 3, \ + { { "batVolt", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_cpu_load_t, batVolt) }, \ + { "sensLoad", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_cpu_load_t, sensLoad) }, \ + { "ctrlLoad", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_cpu_load_t, ctrlLoad) }, \ + } \ +} + + +/** + * @brief Pack a cpu_load message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cpu_load_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, batVolt); + _mav_put_uint8_t(buf, 2, sensLoad); + _mav_put_uint8_t(buf, 3, ctrlLoad); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_cpu_load_t packet; + packet.batVolt = batVolt; + packet.sensLoad = sensLoad; + packet.ctrlLoad = ctrlLoad; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; + return mavlink_finalize_message(msg, system_id, component_id, 4, 75); +} + +/** + * @brief Pack a cpu_load message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_cpu_load_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t sensLoad,uint8_t ctrlLoad,uint16_t batVolt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, batVolt); + _mav_put_uint8_t(buf, 2, sensLoad); + _mav_put_uint8_t(buf, 3, ctrlLoad); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_cpu_load_t packet; + packet.batVolt = batVolt; + packet.sensLoad = sensLoad; + packet.ctrlLoad = ctrlLoad; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_CPU_LOAD; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 75); +} + +/** + * @brief Encode a cpu_load struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param cpu_load C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_cpu_load_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cpu_load_t* cpu_load) +{ + return mavlink_msg_cpu_load_pack(system_id, component_id, msg, cpu_load->sensLoad, cpu_load->ctrlLoad, cpu_load->batVolt); +} + +/** + * @brief Send a cpu_load message + * @param chan MAVLink channel to send the message + * + * @param sensLoad Sensor DSC Load + * @param ctrlLoad Control DSC Load + * @param batVolt Battery Voltage in millivolts + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_cpu_load_send(mavlink_channel_t chan, uint8_t sensLoad, uint8_t ctrlLoad, uint16_t batVolt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, batVolt); + _mav_put_uint8_t(buf, 2, sensLoad); + _mav_put_uint8_t(buf, 3, ctrlLoad); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CPU_LOAD, buf, 4, 75); +#else + mavlink_cpu_load_t packet; + packet.batVolt = batVolt; + packet.sensLoad = sensLoad; + packet.ctrlLoad = ctrlLoad; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CPU_LOAD, (const char *)&packet, 4, 75); +#endif +} + +#endif + +// MESSAGE CPU_LOAD UNPACKING + + +/** + * @brief Get field sensLoad from cpu_load message + * + * @return Sensor DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_sensLoad(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field ctrlLoad from cpu_load message + * + * @return Control DSC Load + */ +static inline uint8_t mavlink_msg_cpu_load_get_ctrlLoad(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field batVolt from cpu_load message + * + * @return Battery Voltage in millivolts + */ +static inline uint16_t mavlink_msg_cpu_load_get_batVolt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a cpu_load message into a struct + * + * @param msg The message to decode + * @param cpu_load C-struct to decode the message contents into + */ +static inline void mavlink_msg_cpu_load_decode(const mavlink_message_t* msg, mavlink_cpu_load_t* cpu_load) +{ +#if MAVLINK_NEED_BYTE_SWAP + cpu_load->batVolt = mavlink_msg_cpu_load_get_batVolt(msg); + cpu_load->sensLoad = mavlink_msg_cpu_load_get_sensLoad(msg); + cpu_load->ctrlLoad = mavlink_msg_cpu_load_get_ctrlLoad(msg); +#else + memcpy(cpu_load, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_ctrl_srfc_pt.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_ctrl_srfc_pt.h new file mode 100644 index 0000000000..dc445e1989 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_ctrl_srfc_pt.h @@ -0,0 +1,166 @@ +// MESSAGE CTRL_SRFC_PT PACKING + +#define MAVLINK_MSG_ID_CTRL_SRFC_PT 181 + +typedef struct __mavlink_ctrl_srfc_pt_t +{ + uint16_t bitfieldPt; ///< Bitfield containing the PT configuration + uint8_t target; ///< The system setting the commands +} mavlink_ctrl_srfc_pt_t; + +#define MAVLINK_MSG_ID_CTRL_SRFC_PT_LEN 3 +#define MAVLINK_MSG_ID_181_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_CTRL_SRFC_PT { \ + "CTRL_SRFC_PT", \ + 2, \ + { { "bitfieldPt", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ctrl_srfc_pt_t, bitfieldPt) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_ctrl_srfc_pt_t, target) }, \ + } \ +} + + +/** + * @brief Pack a ctrl_srfc_pt message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system setting the commands + * @param bitfieldPt Bitfield containing the PT configuration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, uint16_t bitfieldPt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, bitfieldPt); + _mav_put_uint8_t(buf, 2, target); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_ctrl_srfc_pt_t packet; + packet.bitfieldPt = bitfieldPt; + packet.target = target; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; + return mavlink_finalize_message(msg, system_id, component_id, 3, 104); +} + +/** + * @brief Pack a ctrl_srfc_pt message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the commands + * @param bitfieldPt Bitfield containing the PT configuration + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,uint16_t bitfieldPt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, bitfieldPt); + _mav_put_uint8_t(buf, 2, target); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_ctrl_srfc_pt_t packet; + packet.bitfieldPt = bitfieldPt; + packet.target = target; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_CTRL_SRFC_PT; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104); +} + +/** + * @brief Encode a ctrl_srfc_pt struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ctrl_srfc_pt C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt) +{ + return mavlink_msg_ctrl_srfc_pt_pack(system_id, component_id, msg, ctrl_srfc_pt->target, ctrl_srfc_pt->bitfieldPt); +} + +/** + * @brief Send a ctrl_srfc_pt message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the commands + * @param bitfieldPt Bitfield containing the PT configuration + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ctrl_srfc_pt_send(mavlink_channel_t chan, uint8_t target, uint16_t bitfieldPt) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint16_t(buf, 0, bitfieldPt); + _mav_put_uint8_t(buf, 2, target); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CTRL_SRFC_PT, buf, 3, 104); +#else + mavlink_ctrl_srfc_pt_t packet; + packet.bitfieldPt = bitfieldPt; + packet.target = target; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CTRL_SRFC_PT, (const char *)&packet, 3, 104); +#endif +} + +#endif + +// MESSAGE CTRL_SRFC_PT UNPACKING + + +/** + * @brief Get field target from ctrl_srfc_pt message + * + * @return The system setting the commands + */ +static inline uint8_t mavlink_msg_ctrl_srfc_pt_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field bitfieldPt from ctrl_srfc_pt message + * + * @return Bitfield containing the PT configuration + */ +static inline uint16_t mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a ctrl_srfc_pt message into a struct + * + * @param msg The message to decode + * @param ctrl_srfc_pt C-struct to decode the message contents into + */ +static inline void mavlink_msg_ctrl_srfc_pt_decode(const mavlink_message_t* msg, mavlink_ctrl_srfc_pt_t* ctrl_srfc_pt) +{ +#if MAVLINK_NEED_BYTE_SWAP + ctrl_srfc_pt->bitfieldPt = mavlink_msg_ctrl_srfc_pt_get_bitfieldPt(msg); + ctrl_srfc_pt->target = mavlink_msg_ctrl_srfc_pt_get_target(msg); +#else + memcpy(ctrl_srfc_pt, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_data_log.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_data_log.h new file mode 100644 index 0000000000..e852684e18 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_data_log.h @@ -0,0 +1,254 @@ +// MESSAGE DATA_LOG PACKING + +#define MAVLINK_MSG_ID_DATA_LOG 177 + +typedef struct __mavlink_data_log_t +{ + float fl_1; ///< Log value 1 + float fl_2; ///< Log value 2 + float fl_3; ///< Log value 3 + float fl_4; ///< Log value 4 + float fl_5; ///< Log value 5 + float fl_6; ///< Log value 6 +} mavlink_data_log_t; + +#define MAVLINK_MSG_ID_DATA_LOG_LEN 24 +#define MAVLINK_MSG_ID_177_LEN 24 + + + +#define MAVLINK_MESSAGE_INFO_DATA_LOG { \ + "DATA_LOG", \ + 6, \ + { { "fl_1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_data_log_t, fl_1) }, \ + { "fl_2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_data_log_t, fl_2) }, \ + { "fl_3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_data_log_t, fl_3) }, \ + { "fl_4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_data_log_t, fl_4) }, \ + { "fl_5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_data_log_t, fl_5) }, \ + { "fl_6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_data_log_t, fl_6) }, \ + } \ +} + + +/** + * @brief Pack a data_log message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param fl_1 Log value 1 + * @param fl_2 Log value 2 + * @param fl_3 Log value 3 + * @param fl_4 Log value 4 + * @param fl_5 Log value 5 + * @param fl_6 Log value 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_log_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, fl_1); + _mav_put_float(buf, 4, fl_2); + _mav_put_float(buf, 8, fl_3); + _mav_put_float(buf, 12, fl_4); + _mav_put_float(buf, 16, fl_5); + _mav_put_float(buf, 20, fl_6); + + memcpy(_MAV_PAYLOAD(msg), buf, 24); +#else + mavlink_data_log_t packet; + packet.fl_1 = fl_1; + packet.fl_2 = fl_2; + packet.fl_3 = fl_3; + packet.fl_4 = fl_4; + packet.fl_5 = fl_5; + packet.fl_6 = fl_6; + + memcpy(_MAV_PAYLOAD(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_LOG; + return mavlink_finalize_message(msg, system_id, component_id, 24, 167); +} + +/** + * @brief Pack a data_log message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param fl_1 Log value 1 + * @param fl_2 Log value 2 + * @param fl_3 Log value 3 + * @param fl_4 Log value 4 + * @param fl_5 Log value 5 + * @param fl_6 Log value 6 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_data_log_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float fl_1,float fl_2,float fl_3,float fl_4,float fl_5,float fl_6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, fl_1); + _mav_put_float(buf, 4, fl_2); + _mav_put_float(buf, 8, fl_3); + _mav_put_float(buf, 12, fl_4); + _mav_put_float(buf, 16, fl_5); + _mav_put_float(buf, 20, fl_6); + + memcpy(_MAV_PAYLOAD(msg), buf, 24); +#else + mavlink_data_log_t packet; + packet.fl_1 = fl_1; + packet.fl_2 = fl_2; + packet.fl_3 = fl_3; + packet.fl_4 = fl_4; + packet.fl_5 = fl_5; + packet.fl_6 = fl_6; + + memcpy(_MAV_PAYLOAD(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_DATA_LOG; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 167); +} + +/** + * @brief Encode a data_log struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param data_log C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_data_log_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_log_t* data_log) +{ + return mavlink_msg_data_log_pack(system_id, component_id, msg, data_log->fl_1, data_log->fl_2, data_log->fl_3, data_log->fl_4, data_log->fl_5, data_log->fl_6); +} + +/** + * @brief Send a data_log message + * @param chan MAVLink channel to send the message + * + * @param fl_1 Log value 1 + * @param fl_2 Log value 2 + * @param fl_3 Log value 3 + * @param fl_4 Log value 4 + * @param fl_5 Log value 5 + * @param fl_6 Log value 6 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_data_log_send(mavlink_channel_t chan, float fl_1, float fl_2, float fl_3, float fl_4, float fl_5, float fl_6) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, fl_1); + _mav_put_float(buf, 4, fl_2); + _mav_put_float(buf, 8, fl_3); + _mav_put_float(buf, 12, fl_4); + _mav_put_float(buf, 16, fl_5); + _mav_put_float(buf, 20, fl_6); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_LOG, buf, 24, 167); +#else + mavlink_data_log_t packet; + packet.fl_1 = fl_1; + packet.fl_2 = fl_2; + packet.fl_3 = fl_3; + packet.fl_4 = fl_4; + packet.fl_5 = fl_5; + packet.fl_6 = fl_6; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_LOG, (const char *)&packet, 24, 167); +#endif +} + +#endif + +// MESSAGE DATA_LOG UNPACKING + + +/** + * @brief Get field fl_1 from data_log message + * + * @return Log value 1 + */ +static inline float mavlink_msg_data_log_get_fl_1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field fl_2 from data_log message + * + * @return Log value 2 + */ +static inline float mavlink_msg_data_log_get_fl_2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field fl_3 from data_log message + * + * @return Log value 3 + */ +static inline float mavlink_msg_data_log_get_fl_3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field fl_4 from data_log message + * + * @return Log value 4 + */ +static inline float mavlink_msg_data_log_get_fl_4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field fl_5 from data_log message + * + * @return Log value 5 + */ +static inline float mavlink_msg_data_log_get_fl_5(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field fl_6 from data_log message + * + * @return Log value 6 + */ +static inline float mavlink_msg_data_log_get_fl_6(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a data_log message into a struct + * + * @param msg The message to decode + * @param data_log C-struct to decode the message contents into + */ +static inline void mavlink_msg_data_log_decode(const mavlink_message_t* msg, mavlink_data_log_t* data_log) +{ +#if MAVLINK_NEED_BYTE_SWAP + data_log->fl_1 = mavlink_msg_data_log_get_fl_1(msg); + data_log->fl_2 = mavlink_msg_data_log_get_fl_2(msg); + data_log->fl_3 = mavlink_msg_data_log_get_fl_3(msg); + data_log->fl_4 = mavlink_msg_data_log_get_fl_4(msg); + data_log->fl_5 = mavlink_msg_data_log_get_fl_5(msg); + data_log->fl_6 = mavlink_msg_data_log_get_fl_6(msg); +#else + memcpy(data_log, _MAV_PAYLOAD(msg), 24); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_diagnostic.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_diagnostic.h new file mode 100644 index 0000000000..90f64dedd0 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_diagnostic.h @@ -0,0 +1,254 @@ +// MESSAGE DIAGNOSTIC PACKING + +#define MAVLINK_MSG_ID_DIAGNOSTIC 173 + +typedef struct __mavlink_diagnostic_t +{ + float diagFl1; ///< Diagnostic float 1 + float diagFl2; ///< Diagnostic float 2 + float diagFl3; ///< Diagnostic float 3 + int16_t diagSh1; ///< Diagnostic short 1 + int16_t diagSh2; ///< Diagnostic short 2 + int16_t diagSh3; ///< Diagnostic short 3 +} mavlink_diagnostic_t; + +#define MAVLINK_MSG_ID_DIAGNOSTIC_LEN 18 +#define MAVLINK_MSG_ID_173_LEN 18 + + + +#define MAVLINK_MESSAGE_INFO_DIAGNOSTIC { \ + "DIAGNOSTIC", \ + 6, \ + { { "diagFl1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_diagnostic_t, diagFl1) }, \ + { "diagFl2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_diagnostic_t, diagFl2) }, \ + { "diagFl3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_diagnostic_t, diagFl3) }, \ + { "diagSh1", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_diagnostic_t, diagSh1) }, \ + { "diagSh2", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_diagnostic_t, diagSh2) }, \ + { "diagSh3", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_diagnostic_t, diagSh3) }, \ + } \ +} + + +/** + * @brief Pack a diagnostic message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diagnostic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, diagFl1); + _mav_put_float(buf, 4, diagFl2); + _mav_put_float(buf, 8, diagFl3); + _mav_put_int16_t(buf, 12, diagSh1); + _mav_put_int16_t(buf, 14, diagSh2); + _mav_put_int16_t(buf, 16, diagSh3); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_diagnostic_t packet; + packet.diagFl1 = diagFl1; + packet.diagFl2 = diagFl2; + packet.diagFl3 = diagFl3; + packet.diagSh1 = diagSh1; + packet.diagSh2 = diagSh2; + packet.diagSh3 = diagSh3; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; + return mavlink_finalize_message(msg, system_id, component_id, 18, 2); +} + +/** + * @brief Pack a diagnostic message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_diagnostic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float diagFl1,float diagFl2,float diagFl3,int16_t diagSh1,int16_t diagSh2,int16_t diagSh3) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, diagFl1); + _mav_put_float(buf, 4, diagFl2); + _mav_put_float(buf, 8, diagFl3); + _mav_put_int16_t(buf, 12, diagSh1); + _mav_put_int16_t(buf, 14, diagSh2); + _mav_put_int16_t(buf, 16, diagSh3); + + memcpy(_MAV_PAYLOAD(msg), buf, 18); +#else + mavlink_diagnostic_t packet; + packet.diagFl1 = diagFl1; + packet.diagFl2 = diagFl2; + packet.diagFl3 = diagFl3; + packet.diagSh1 = diagSh1; + packet.diagSh2 = diagSh2; + packet.diagSh3 = diagSh3; + + memcpy(_MAV_PAYLOAD(msg), &packet, 18); +#endif + + msg->msgid = MAVLINK_MSG_ID_DIAGNOSTIC; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 2); +} + +/** + * @brief Encode a diagnostic struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param diagnostic C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_diagnostic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_diagnostic_t* diagnostic) +{ + return mavlink_msg_diagnostic_pack(system_id, component_id, msg, diagnostic->diagFl1, diagnostic->diagFl2, diagnostic->diagFl3, diagnostic->diagSh1, diagnostic->diagSh2, diagnostic->diagSh3); +} + +/** + * @brief Send a diagnostic message + * @param chan MAVLink channel to send the message + * + * @param diagFl1 Diagnostic float 1 + * @param diagFl2 Diagnostic float 2 + * @param diagFl3 Diagnostic float 3 + * @param diagSh1 Diagnostic short 1 + * @param diagSh2 Diagnostic short 2 + * @param diagSh3 Diagnostic short 3 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_diagnostic_send(mavlink_channel_t chan, float diagFl1, float diagFl2, float diagFl3, int16_t diagSh1, int16_t diagSh2, int16_t diagSh3) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[18]; + _mav_put_float(buf, 0, diagFl1); + _mav_put_float(buf, 4, diagFl2); + _mav_put_float(buf, 8, diagFl3); + _mav_put_int16_t(buf, 12, diagSh1); + _mav_put_int16_t(buf, 14, diagSh2); + _mav_put_int16_t(buf, 16, diagSh3); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, buf, 18, 2); +#else + mavlink_diagnostic_t packet; + packet.diagFl1 = diagFl1; + packet.diagFl2 = diagFl2; + packet.diagFl3 = diagFl3; + packet.diagSh1 = diagSh1; + packet.diagSh2 = diagSh2; + packet.diagSh3 = diagSh3; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIAGNOSTIC, (const char *)&packet, 18, 2); +#endif +} + +#endif + +// MESSAGE DIAGNOSTIC UNPACKING + + +/** + * @brief Get field diagFl1 from diagnostic message + * + * @return Diagnostic float 1 + */ +static inline float mavlink_msg_diagnostic_get_diagFl1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field diagFl2 from diagnostic message + * + * @return Diagnostic float 2 + */ +static inline float mavlink_msg_diagnostic_get_diagFl2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field diagFl3 from diagnostic message + * + * @return Diagnostic float 3 + */ +static inline float mavlink_msg_diagnostic_get_diagFl3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field diagSh1 from diagnostic message + * + * @return Diagnostic short 1 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 12); +} + +/** + * @brief Get field diagSh2 from diagnostic message + * + * @return Diagnostic short 2 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 14); +} + +/** + * @brief Get field diagSh3 from diagnostic message + * + * @return Diagnostic short 3 + */ +static inline int16_t mavlink_msg_diagnostic_get_diagSh3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 16); +} + +/** + * @brief Decode a diagnostic message into a struct + * + * @param msg The message to decode + * @param diagnostic C-struct to decode the message contents into + */ +static inline void mavlink_msg_diagnostic_decode(const mavlink_message_t* msg, mavlink_diagnostic_t* diagnostic) +{ +#if MAVLINK_NEED_BYTE_SWAP + diagnostic->diagFl1 = mavlink_msg_diagnostic_get_diagFl1(msg); + diagnostic->diagFl2 = mavlink_msg_diagnostic_get_diagFl2(msg); + diagnostic->diagFl3 = mavlink_msg_diagnostic_get_diagFl3(msg); + diagnostic->diagSh1 = mavlink_msg_diagnostic_get_diagSh1(msg); + diagnostic->diagSh2 = mavlink_msg_diagnostic_get_diagSh2(msg); + diagnostic->diagSh3 = mavlink_msg_diagnostic_get_diagSh3(msg); +#else + memcpy(diagnostic, _MAV_PAYLOAD(msg), 18); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_gps_date_time.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_gps_date_time.h new file mode 100644 index 0000000000..d4fb12bf87 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_gps_date_time.h @@ -0,0 +1,276 @@ +// MESSAGE GPS_DATE_TIME PACKING + +#define MAVLINK_MSG_ID_GPS_DATE_TIME 179 + +typedef struct __mavlink_gps_date_time_t +{ + uint8_t year; ///< Year reported by Gps + uint8_t month; ///< Month reported by Gps + uint8_t day; ///< Day reported by Gps + uint8_t hour; ///< Hour reported by Gps + uint8_t min; ///< Min reported by Gps + uint8_t sec; ///< Sec reported by Gps + uint8_t visSat; ///< Visible sattelites reported by Gps +} mavlink_gps_date_time_t; + +#define MAVLINK_MSG_ID_GPS_DATE_TIME_LEN 7 +#define MAVLINK_MSG_ID_179_LEN 7 + + + +#define MAVLINK_MESSAGE_INFO_GPS_DATE_TIME { \ + "GPS_DATE_TIME", \ + 7, \ + { { "year", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_date_time_t, year) }, \ + { "month", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_date_time_t, month) }, \ + { "day", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_date_time_t, day) }, \ + { "hour", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_gps_date_time_t, hour) }, \ + { "min", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_gps_date_time_t, min) }, \ + { "sec", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_gps_date_time_t, sec) }, \ + { "visSat", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gps_date_time_t, visSat) }, \ + } \ +} + + +/** + * @brief Pack a gps_date_time message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param year Year reported by Gps + * @param month Month reported by Gps + * @param day Day reported by Gps + * @param hour Hour reported by Gps + * @param min Min reported by Gps + * @param sec Sec reported by Gps + * @param visSat Visible sattelites reported by Gps + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_date_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[7]; + _mav_put_uint8_t(buf, 0, year); + _mav_put_uint8_t(buf, 1, month); + _mav_put_uint8_t(buf, 2, day); + _mav_put_uint8_t(buf, 3, hour); + _mav_put_uint8_t(buf, 4, min); + _mav_put_uint8_t(buf, 5, sec); + _mav_put_uint8_t(buf, 6, visSat); + + memcpy(_MAV_PAYLOAD(msg), buf, 7); +#else + mavlink_gps_date_time_t packet; + packet.year = year; + packet.month = month; + packet.day = day; + packet.hour = hour; + packet.min = min; + packet.sec = sec; + packet.visSat = visSat; + + memcpy(_MAV_PAYLOAD(msg), &packet, 7); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; + return mavlink_finalize_message(msg, system_id, component_id, 7, 16); +} + +/** + * @brief Pack a gps_date_time message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param year Year reported by Gps + * @param month Month reported by Gps + * @param day Day reported by Gps + * @param hour Hour reported by Gps + * @param min Min reported by Gps + * @param sec Sec reported by Gps + * @param visSat Visible sattelites reported by Gps + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_date_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t year,uint8_t month,uint8_t day,uint8_t hour,uint8_t min,uint8_t sec,uint8_t visSat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[7]; + _mav_put_uint8_t(buf, 0, year); + _mav_put_uint8_t(buf, 1, month); + _mav_put_uint8_t(buf, 2, day); + _mav_put_uint8_t(buf, 3, hour); + _mav_put_uint8_t(buf, 4, min); + _mav_put_uint8_t(buf, 5, sec); + _mav_put_uint8_t(buf, 6, visSat); + + memcpy(_MAV_PAYLOAD(msg), buf, 7); +#else + mavlink_gps_date_time_t packet; + packet.year = year; + packet.month = month; + packet.day = day; + packet.hour = hour; + packet.min = min; + packet.sec = sec; + packet.visSat = visSat; + + memcpy(_MAV_PAYLOAD(msg), &packet, 7); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_DATE_TIME; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 16); +} + +/** + * @brief Encode a gps_date_time struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_date_time C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_date_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_date_time_t* gps_date_time) +{ + return mavlink_msg_gps_date_time_pack(system_id, component_id, msg, gps_date_time->year, gps_date_time->month, gps_date_time->day, gps_date_time->hour, gps_date_time->min, gps_date_time->sec, gps_date_time->visSat); +} + +/** + * @brief Send a gps_date_time message + * @param chan MAVLink channel to send the message + * + * @param year Year reported by Gps + * @param month Month reported by Gps + * @param day Day reported by Gps + * @param hour Hour reported by Gps + * @param min Min reported by Gps + * @param sec Sec reported by Gps + * @param visSat Visible sattelites reported by Gps + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_date_time_send(mavlink_channel_t chan, uint8_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec, uint8_t visSat) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[7]; + _mav_put_uint8_t(buf, 0, year); + _mav_put_uint8_t(buf, 1, month); + _mav_put_uint8_t(buf, 2, day); + _mav_put_uint8_t(buf, 3, hour); + _mav_put_uint8_t(buf, 4, min); + _mav_put_uint8_t(buf, 5, sec); + _mav_put_uint8_t(buf, 6, visSat); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_DATE_TIME, buf, 7, 16); +#else + mavlink_gps_date_time_t packet; + packet.year = year; + packet.month = month; + packet.day = day; + packet.hour = hour; + packet.min = min; + packet.sec = sec; + packet.visSat = visSat; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_DATE_TIME, (const char *)&packet, 7, 16); +#endif +} + +#endif + +// MESSAGE GPS_DATE_TIME UNPACKING + + +/** + * @brief Get field year from gps_date_time message + * + * @return Year reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_year(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field month from gps_date_time message + * + * @return Month reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_month(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field day from gps_date_time message + * + * @return Day reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_day(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field hour from gps_date_time message + * + * @return Hour reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_hour(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field min from gps_date_time message + * + * @return Min reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_min(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 4); +} + +/** + * @brief Get field sec from gps_date_time message + * + * @return Sec reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_sec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 5); +} + +/** + * @brief Get field visSat from gps_date_time message + * + * @return Visible sattelites reported by Gps + */ +static inline uint8_t mavlink_msg_gps_date_time_get_visSat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 6); +} + +/** + * @brief Decode a gps_date_time message into a struct + * + * @param msg The message to decode + * @param gps_date_time C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_date_time_decode(const mavlink_message_t* msg, mavlink_gps_date_time_t* gps_date_time) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_date_time->year = mavlink_msg_gps_date_time_get_year(msg); + gps_date_time->month = mavlink_msg_gps_date_time_get_month(msg); + gps_date_time->day = mavlink_msg_gps_date_time_get_day(msg); + gps_date_time->hour = mavlink_msg_gps_date_time_get_hour(msg); + gps_date_time->min = mavlink_msg_gps_date_time_get_min(msg); + gps_date_time->sec = mavlink_msg_gps_date_time_get_sec(msg); + gps_date_time->visSat = mavlink_msg_gps_date_time_get_visSat(msg); +#else + memcpy(gps_date_time, _MAV_PAYLOAD(msg), 7); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_mid_lvl_cmds.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_mid_lvl_cmds.h new file mode 100644 index 0000000000..59e4012b12 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_mid_lvl_cmds.h @@ -0,0 +1,210 @@ +// MESSAGE MID_LVL_CMDS PACKING + +#define MAVLINK_MSG_ID_MID_LVL_CMDS 180 + +typedef struct __mavlink_mid_lvl_cmds_t +{ + float hCommand; ///< Commanded Airspeed + float uCommand; ///< Log value 2 + float rCommand; ///< Log value 3 + uint8_t target; ///< The system setting the commands +} mavlink_mid_lvl_cmds_t; + +#define MAVLINK_MSG_ID_MID_LVL_CMDS_LEN 13 +#define MAVLINK_MSG_ID_180_LEN 13 + + + +#define MAVLINK_MESSAGE_INFO_MID_LVL_CMDS { \ + "MID_LVL_CMDS", \ + 4, \ + { { "hCommand", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mid_lvl_cmds_t, hCommand) }, \ + { "uCommand", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mid_lvl_cmds_t, uCommand) }, \ + { "rCommand", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mid_lvl_cmds_t, rCommand) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mid_lvl_cmds_t, target) }, \ + } \ +} + + +/** + * @brief Pack a mid_lvl_cmds message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system setting the commands + * @param hCommand Commanded Airspeed + * @param uCommand Log value 2 + * @param rCommand Log value 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mid_lvl_cmds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, float hCommand, float uCommand, float rCommand) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, hCommand); + _mav_put_float(buf, 4, uCommand); + _mav_put_float(buf, 8, rCommand); + _mav_put_uint8_t(buf, 12, target); + + memcpy(_MAV_PAYLOAD(msg), buf, 13); +#else + mavlink_mid_lvl_cmds_t packet; + packet.hCommand = hCommand; + packet.uCommand = uCommand; + packet.rCommand = rCommand; + packet.target = target; + + memcpy(_MAV_PAYLOAD(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; + return mavlink_finalize_message(msg, system_id, component_id, 13, 146); +} + +/** + * @brief Pack a mid_lvl_cmds message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system setting the commands + * @param hCommand Commanded Airspeed + * @param uCommand Log value 2 + * @param rCommand Log value 3 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_mid_lvl_cmds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,float hCommand,float uCommand,float rCommand) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, hCommand); + _mav_put_float(buf, 4, uCommand); + _mav_put_float(buf, 8, rCommand); + _mav_put_uint8_t(buf, 12, target); + + memcpy(_MAV_PAYLOAD(msg), buf, 13); +#else + mavlink_mid_lvl_cmds_t packet; + packet.hCommand = hCommand; + packet.uCommand = uCommand; + packet.rCommand = rCommand; + packet.target = target; + + memcpy(_MAV_PAYLOAD(msg), &packet, 13); +#endif + + msg->msgid = MAVLINK_MSG_ID_MID_LVL_CMDS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 146); +} + +/** + * @brief Encode a mid_lvl_cmds struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param mid_lvl_cmds C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_mid_lvl_cmds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mid_lvl_cmds_t* mid_lvl_cmds) +{ + return mavlink_msg_mid_lvl_cmds_pack(system_id, component_id, msg, mid_lvl_cmds->target, mid_lvl_cmds->hCommand, mid_lvl_cmds->uCommand, mid_lvl_cmds->rCommand); +} + +/** + * @brief Send a mid_lvl_cmds message + * @param chan MAVLink channel to send the message + * + * @param target The system setting the commands + * @param hCommand Commanded Airspeed + * @param uCommand Log value 2 + * @param rCommand Log value 3 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_mid_lvl_cmds_send(mavlink_channel_t chan, uint8_t target, float hCommand, float uCommand, float rCommand) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[13]; + _mav_put_float(buf, 0, hCommand); + _mav_put_float(buf, 4, uCommand); + _mav_put_float(buf, 8, rCommand); + _mav_put_uint8_t(buf, 12, target); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MID_LVL_CMDS, buf, 13, 146); +#else + mavlink_mid_lvl_cmds_t packet; + packet.hCommand = hCommand; + packet.uCommand = uCommand; + packet.rCommand = rCommand; + packet.target = target; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MID_LVL_CMDS, (const char *)&packet, 13, 146); +#endif +} + +#endif + +// MESSAGE MID_LVL_CMDS UNPACKING + + +/** + * @brief Get field target from mid_lvl_cmds message + * + * @return The system setting the commands + */ +static inline uint8_t mavlink_msg_mid_lvl_cmds_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 12); +} + +/** + * @brief Get field hCommand from mid_lvl_cmds message + * + * @return Commanded Airspeed + */ +static inline float mavlink_msg_mid_lvl_cmds_get_hCommand(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field uCommand from mid_lvl_cmds message + * + * @return Log value 2 + */ +static inline float mavlink_msg_mid_lvl_cmds_get_uCommand(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field rCommand from mid_lvl_cmds message + * + * @return Log value 3 + */ +static inline float mavlink_msg_mid_lvl_cmds_get_rCommand(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Decode a mid_lvl_cmds message into a struct + * + * @param msg The message to decode + * @param mid_lvl_cmds C-struct to decode the message contents into + */ +static inline void mavlink_msg_mid_lvl_cmds_decode(const mavlink_message_t* msg, mavlink_mid_lvl_cmds_t* mid_lvl_cmds) +{ +#if MAVLINK_NEED_BYTE_SWAP + mid_lvl_cmds->hCommand = mavlink_msg_mid_lvl_cmds_get_hCommand(msg); + mid_lvl_cmds->uCommand = mavlink_msg_mid_lvl_cmds_get_uCommand(msg); + mid_lvl_cmds->rCommand = mavlink_msg_mid_lvl_cmds_get_rCommand(msg); + mid_lvl_cmds->target = mavlink_msg_mid_lvl_cmds_get_target(msg); +#else + memcpy(mid_lvl_cmds, _MAV_PAYLOAD(msg), 13); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_sensor_bias.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_sensor_bias.h new file mode 100644 index 0000000000..3bf6803a60 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_sensor_bias.h @@ -0,0 +1,254 @@ +// MESSAGE SENSOR_BIAS PACKING + +#define MAVLINK_MSG_ID_SENSOR_BIAS 172 + +typedef struct __mavlink_sensor_bias_t +{ + float axBias; ///< Accelerometer X bias (m/s) + float ayBias; ///< Accelerometer Y bias (m/s) + float azBias; ///< Accelerometer Z bias (m/s) + float gxBias; ///< Gyro X bias (rad/s) + float gyBias; ///< Gyro Y bias (rad/s) + float gzBias; ///< Gyro Z bias (rad/s) +} mavlink_sensor_bias_t; + +#define MAVLINK_MSG_ID_SENSOR_BIAS_LEN 24 +#define MAVLINK_MSG_ID_172_LEN 24 + + + +#define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \ + "SENSOR_BIAS", \ + 6, \ + { { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \ + { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \ + { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \ + { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \ + { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \ + { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \ + } \ +} + + +/** + * @brief Pack a sensor_bias message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, axBias); + _mav_put_float(buf, 4, ayBias); + _mav_put_float(buf, 8, azBias); + _mav_put_float(buf, 12, gxBias); + _mav_put_float(buf, 16, gyBias); + _mav_put_float(buf, 20, gzBias); + + memcpy(_MAV_PAYLOAD(msg), buf, 24); +#else + mavlink_sensor_bias_t packet; + packet.axBias = axBias; + packet.ayBias = ayBias; + packet.azBias = azBias; + packet.gxBias = gxBias; + packet.gyBias = gyBias; + packet.gzBias = gzBias; + + memcpy(_MAV_PAYLOAD(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; + return mavlink_finalize_message(msg, system_id, component_id, 24, 168); +} + +/** + * @brief Pack a sensor_bias message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float axBias,float ayBias,float azBias,float gxBias,float gyBias,float gzBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, axBias); + _mav_put_float(buf, 4, ayBias); + _mav_put_float(buf, 8, azBias); + _mav_put_float(buf, 12, gxBias); + _mav_put_float(buf, 16, gyBias); + _mav_put_float(buf, 20, gzBias); + + memcpy(_MAV_PAYLOAD(msg), buf, 24); +#else + mavlink_sensor_bias_t packet; + packet.axBias = axBias; + packet.ayBias = ayBias; + packet.azBias = azBias; + packet.gxBias = gxBias; + packet.gyBias = gyBias; + packet.gzBias = gzBias; + + memcpy(_MAV_PAYLOAD(msg), &packet, 24); +#endif + + msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 168); +} + +/** + * @brief Encode a sensor_bias struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param sensor_bias C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias) +{ + return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias); +} + +/** + * @brief Send a sensor_bias message + * @param chan MAVLink channel to send the message + * + * @param axBias Accelerometer X bias (m/s) + * @param ayBias Accelerometer Y bias (m/s) + * @param azBias Accelerometer Z bias (m/s) + * @param gxBias Gyro X bias (rad/s) + * @param gyBias Gyro Y bias (rad/s) + * @param gzBias Gyro Z bias (rad/s) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[24]; + _mav_put_float(buf, 0, axBias); + _mav_put_float(buf, 4, ayBias); + _mav_put_float(buf, 8, azBias); + _mav_put_float(buf, 12, gxBias); + _mav_put_float(buf, 16, gyBias); + _mav_put_float(buf, 20, gzBias); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, 24, 168); +#else + mavlink_sensor_bias_t packet; + packet.axBias = axBias; + packet.ayBias = ayBias; + packet.azBias = azBias; + packet.gxBias = gxBias; + packet.gyBias = gyBias; + packet.gzBias = gzBias; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)&packet, 24, 168); +#endif +} + +#endif + +// MESSAGE SENSOR_BIAS UNPACKING + + +/** + * @brief Get field axBias from sensor_bias message + * + * @return Accelerometer X bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field ayBias from sensor_bias message + * + * @return Accelerometer Y bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field azBias from sensor_bias message + * + * @return Accelerometer Z bias (m/s) + */ +static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field gxBias from sensor_bias message + * + * @return Gyro X bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field gyBias from sensor_bias message + * + * @return Gyro Y bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field gzBias from sensor_bias message + * + * @return Gyro Z bias (rad/s) + */ +static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a sensor_bias message into a struct + * + * @param msg The message to decode + * @param sensor_bias C-struct to decode the message contents into + */ +static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias) +{ +#if MAVLINK_NEED_BYTE_SWAP + sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg); + sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg); + sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg); + sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg); + sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg); + sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg); +#else + memcpy(sensor_bias, _MAV_PAYLOAD(msg), 24); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_action.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_action.h new file mode 100644 index 0000000000..2382a17c47 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_action.h @@ -0,0 +1,188 @@ +// MESSAGE SLUGS_ACTION PACKING + +#define MAVLINK_MSG_ID_SLUGS_ACTION 183 + +typedef struct __mavlink_slugs_action_t +{ + uint16_t actionVal; ///< Value associated with the action + uint8_t target; ///< The system reporting the action + uint8_t actionId; ///< Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names +} mavlink_slugs_action_t; + +#define MAVLINK_MSG_ID_SLUGS_ACTION_LEN 4 +#define MAVLINK_MSG_ID_183_LEN 4 + + + +#define MAVLINK_MESSAGE_INFO_SLUGS_ACTION { \ + "SLUGS_ACTION", \ + 3, \ + { { "actionVal", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_slugs_action_t, actionVal) }, \ + { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_slugs_action_t, target) }, \ + { "actionId", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_slugs_action_t, actionId) }, \ + } \ +} + + +/** + * @brief Pack a slugs_action message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param target The system reporting the action + * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + * @param actionVal Value associated with the action + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t target, uint8_t actionId, uint16_t actionVal) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, actionVal); + _mav_put_uint8_t(buf, 2, target); + _mav_put_uint8_t(buf, 3, actionId); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_slugs_action_t packet; + packet.actionVal = actionVal; + packet.target = target; + packet.actionId = actionId; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; + return mavlink_finalize_message(msg, system_id, component_id, 4, 65); +} + +/** + * @brief Pack a slugs_action message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param target The system reporting the action + * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + * @param actionVal Value associated with the action + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t target,uint8_t actionId,uint16_t actionVal) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, actionVal); + _mav_put_uint8_t(buf, 2, target); + _mav_put_uint8_t(buf, 3, actionId); + + memcpy(_MAV_PAYLOAD(msg), buf, 4); +#else + mavlink_slugs_action_t packet; + packet.actionVal = actionVal; + packet.target = target; + packet.actionId = actionId; + + memcpy(_MAV_PAYLOAD(msg), &packet, 4); +#endif + + msg->msgid = MAVLINK_MSG_ID_SLUGS_ACTION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 65); +} + +/** + * @brief Encode a slugs_action struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param slugs_action C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_slugs_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_action_t* slugs_action) +{ + return mavlink_msg_slugs_action_pack(system_id, component_id, msg, slugs_action->target, slugs_action->actionId, slugs_action->actionVal); +} + +/** + * @brief Send a slugs_action message + * @param chan MAVLink channel to send the message + * + * @param target The system reporting the action + * @param actionId Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + * @param actionVal Value associated with the action + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_slugs_action_send(mavlink_channel_t chan, uint8_t target, uint8_t actionId, uint16_t actionVal) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[4]; + _mav_put_uint16_t(buf, 0, actionVal); + _mav_put_uint8_t(buf, 2, target); + _mav_put_uint8_t(buf, 3, actionId); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SLUGS_ACTION, buf, 4, 65); +#else + mavlink_slugs_action_t packet; + packet.actionVal = actionVal; + packet.target = target; + packet.actionId = actionId; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SLUGS_ACTION, (const char *)&packet, 4, 65); +#endif +} + +#endif + +// MESSAGE SLUGS_ACTION UNPACKING + + +/** + * @brief Get field target from slugs_action message + * + * @return The system reporting the action + */ +static inline uint8_t mavlink_msg_slugs_action_get_target(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Get field actionId from slugs_action message + * + * @return Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + */ +static inline uint8_t mavlink_msg_slugs_action_get_actionId(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 3); +} + +/** + * @brief Get field actionVal from slugs_action message + * + * @return Value associated with the action + */ +static inline uint16_t mavlink_msg_slugs_action_get_actionVal(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 0); +} + +/** + * @brief Decode a slugs_action message into a struct + * + * @param msg The message to decode + * @param slugs_action C-struct to decode the message contents into + */ +static inline void mavlink_msg_slugs_action_decode(const mavlink_message_t* msg, mavlink_slugs_action_t* slugs_action) +{ +#if MAVLINK_NEED_BYTE_SWAP + slugs_action->actionVal = mavlink_msg_slugs_action_get_actionVal(msg); + slugs_action->target = mavlink_msg_slugs_action_get_target(msg); + slugs_action->actionId = mavlink_msg_slugs_action_get_actionId(msg); +#else + memcpy(slugs_action, _MAV_PAYLOAD(msg), 4); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_navigation.h b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_navigation.h new file mode 100644 index 0000000000..a0253a8483 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/mavlink_msg_slugs_navigation.h @@ -0,0 +1,320 @@ +// MESSAGE SLUGS_NAVIGATION PACKING + +#define MAVLINK_MSG_ID_SLUGS_NAVIGATION 176 + +typedef struct __mavlink_slugs_navigation_t +{ + float u_m; ///< Measured Airspeed prior to the Nav Filter + float phi_c; ///< Commanded Roll + float theta_c; ///< Commanded Pitch + float psiDot_c; ///< Commanded Turn rate + float ay_body; ///< Y component of the body acceleration + float totalDist; ///< Total Distance to Run on this leg of Navigation + float dist2Go; ///< Remaining distance to Run on this leg of Navigation + uint8_t fromWP; ///< Origin WP + uint8_t toWP; ///< Destination WP +} mavlink_slugs_navigation_t; + +#define MAVLINK_MSG_ID_SLUGS_NAVIGATION_LEN 30 +#define MAVLINK_MSG_ID_176_LEN 30 + + + +#define MAVLINK_MESSAGE_INFO_SLUGS_NAVIGATION { \ + "SLUGS_NAVIGATION", \ + 9, \ + { { "u_m", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_slugs_navigation_t, u_m) }, \ + { "phi_c", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_slugs_navigation_t, phi_c) }, \ + { "theta_c", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_slugs_navigation_t, theta_c) }, \ + { "psiDot_c", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_slugs_navigation_t, psiDot_c) }, \ + { "ay_body", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_slugs_navigation_t, ay_body) }, \ + { "totalDist", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_slugs_navigation_t, totalDist) }, \ + { "dist2Go", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_slugs_navigation_t, dist2Go) }, \ + { "fromWP", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_slugs_navigation_t, fromWP) }, \ + { "toWP", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_slugs_navigation_t, toWP) }, \ + } \ +} + + +/** + * @brief Pack a slugs_navigation message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param u_m Measured Airspeed prior to the Nav Filter + * @param phi_c Commanded Roll + * @param theta_c Commanded Pitch + * @param psiDot_c Commanded Turn rate + * @param ay_body Y component of the body acceleration + * @param totalDist Total Distance to Run on this leg of Navigation + * @param dist2Go Remaining distance to Run on this leg of Navigation + * @param fromWP Origin WP + * @param toWP Destination WP + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_navigation_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_float(buf, 0, u_m); + _mav_put_float(buf, 4, phi_c); + _mav_put_float(buf, 8, theta_c); + _mav_put_float(buf, 12, psiDot_c); + _mav_put_float(buf, 16, ay_body); + _mav_put_float(buf, 20, totalDist); + _mav_put_float(buf, 24, dist2Go); + _mav_put_uint8_t(buf, 28, fromWP); + _mav_put_uint8_t(buf, 29, toWP); + + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_slugs_navigation_t packet; + packet.u_m = u_m; + packet.phi_c = phi_c; + packet.theta_c = theta_c; + packet.psiDot_c = psiDot_c; + packet.ay_body = ay_body; + packet.totalDist = totalDist; + packet.dist2Go = dist2Go; + packet.fromWP = fromWP; + packet.toWP = toWP; + + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; + return mavlink_finalize_message(msg, system_id, component_id, 30, 120); +} + +/** + * @brief Pack a slugs_navigation message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param u_m Measured Airspeed prior to the Nav Filter + * @param phi_c Commanded Roll + * @param theta_c Commanded Pitch + * @param psiDot_c Commanded Turn rate + * @param ay_body Y component of the body acceleration + * @param totalDist Total Distance to Run on this leg of Navigation + * @param dist2Go Remaining distance to Run on this leg of Navigation + * @param fromWP Origin WP + * @param toWP Destination WP + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_slugs_navigation_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + float u_m,float phi_c,float theta_c,float psiDot_c,float ay_body,float totalDist,float dist2Go,uint8_t fromWP,uint8_t toWP) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_float(buf, 0, u_m); + _mav_put_float(buf, 4, phi_c); + _mav_put_float(buf, 8, theta_c); + _mav_put_float(buf, 12, psiDot_c); + _mav_put_float(buf, 16, ay_body); + _mav_put_float(buf, 20, totalDist); + _mav_put_float(buf, 24, dist2Go); + _mav_put_uint8_t(buf, 28, fromWP); + _mav_put_uint8_t(buf, 29, toWP); + + memcpy(_MAV_PAYLOAD(msg), buf, 30); +#else + mavlink_slugs_navigation_t packet; + packet.u_m = u_m; + packet.phi_c = phi_c; + packet.theta_c = theta_c; + packet.psiDot_c = psiDot_c; + packet.ay_body = ay_body; + packet.totalDist = totalDist; + packet.dist2Go = dist2Go; + packet.fromWP = fromWP; + packet.toWP = toWP; + + memcpy(_MAV_PAYLOAD(msg), &packet, 30); +#endif + + msg->msgid = MAVLINK_MSG_ID_SLUGS_NAVIGATION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 120); +} + +/** + * @brief Encode a slugs_navigation struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param slugs_navigation C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_slugs_navigation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_slugs_navigation_t* slugs_navigation) +{ + return mavlink_msg_slugs_navigation_pack(system_id, component_id, msg, slugs_navigation->u_m, slugs_navigation->phi_c, slugs_navigation->theta_c, slugs_navigation->psiDot_c, slugs_navigation->ay_body, slugs_navigation->totalDist, slugs_navigation->dist2Go, slugs_navigation->fromWP, slugs_navigation->toWP); +} + +/** + * @brief Send a slugs_navigation message + * @param chan MAVLink channel to send the message + * + * @param u_m Measured Airspeed prior to the Nav Filter + * @param phi_c Commanded Roll + * @param theta_c Commanded Pitch + * @param psiDot_c Commanded Turn rate + * @param ay_body Y component of the body acceleration + * @param totalDist Total Distance to Run on this leg of Navigation + * @param dist2Go Remaining distance to Run on this leg of Navigation + * @param fromWP Origin WP + * @param toWP Destination WP + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_slugs_navigation_send(mavlink_channel_t chan, float u_m, float phi_c, float theta_c, float psiDot_c, float ay_body, float totalDist, float dist2Go, uint8_t fromWP, uint8_t toWP) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[30]; + _mav_put_float(buf, 0, u_m); + _mav_put_float(buf, 4, phi_c); + _mav_put_float(buf, 8, theta_c); + _mav_put_float(buf, 12, psiDot_c); + _mav_put_float(buf, 16, ay_body); + _mav_put_float(buf, 20, totalDist); + _mav_put_float(buf, 24, dist2Go); + _mav_put_uint8_t(buf, 28, fromWP); + _mav_put_uint8_t(buf, 29, toWP); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SLUGS_NAVIGATION, buf, 30, 120); +#else + mavlink_slugs_navigation_t packet; + packet.u_m = u_m; + packet.phi_c = phi_c; + packet.theta_c = theta_c; + packet.psiDot_c = psiDot_c; + packet.ay_body = ay_body; + packet.totalDist = totalDist; + packet.dist2Go = dist2Go; + packet.fromWP = fromWP; + packet.toWP = toWP; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SLUGS_NAVIGATION, (const char *)&packet, 30, 120); +#endif +} + +#endif + +// MESSAGE SLUGS_NAVIGATION UNPACKING + + +/** + * @brief Get field u_m from slugs_navigation message + * + * @return Measured Airspeed prior to the Nav Filter + */ +static inline float mavlink_msg_slugs_navigation_get_u_m(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 0); +} + +/** + * @brief Get field phi_c from slugs_navigation message + * + * @return Commanded Roll + */ +static inline float mavlink_msg_slugs_navigation_get_phi_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field theta_c from slugs_navigation message + * + * @return Commanded Pitch + */ +static inline float mavlink_msg_slugs_navigation_get_theta_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field psiDot_c from slugs_navigation message + * + * @return Commanded Turn rate + */ +static inline float mavlink_msg_slugs_navigation_get_psiDot_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field ay_body from slugs_navigation message + * + * @return Y component of the body acceleration + */ +static inline float mavlink_msg_slugs_navigation_get_ay_body(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field totalDist from slugs_navigation message + * + * @return Total Distance to Run on this leg of Navigation + */ +static inline float mavlink_msg_slugs_navigation_get_totalDist(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field dist2Go from slugs_navigation message + * + * @return Remaining distance to Run on this leg of Navigation + */ +static inline float mavlink_msg_slugs_navigation_get_dist2Go(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field fromWP from slugs_navigation message + * + * @return Origin WP + */ +static inline uint8_t mavlink_msg_slugs_navigation_get_fromWP(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field toWP from slugs_navigation message + * + * @return Destination WP + */ +static inline uint8_t mavlink_msg_slugs_navigation_get_toWP(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 29); +} + +/** + * @brief Decode a slugs_navigation message into a struct + * + * @param msg The message to decode + * @param slugs_navigation C-struct to decode the message contents into + */ +static inline void mavlink_msg_slugs_navigation_decode(const mavlink_message_t* msg, mavlink_slugs_navigation_t* slugs_navigation) +{ +#if MAVLINK_NEED_BYTE_SWAP + slugs_navigation->u_m = mavlink_msg_slugs_navigation_get_u_m(msg); + slugs_navigation->phi_c = mavlink_msg_slugs_navigation_get_phi_c(msg); + slugs_navigation->theta_c = mavlink_msg_slugs_navigation_get_theta_c(msg); + slugs_navigation->psiDot_c = mavlink_msg_slugs_navigation_get_psiDot_c(msg); + slugs_navigation->ay_body = mavlink_msg_slugs_navigation_get_ay_body(msg); + slugs_navigation->totalDist = mavlink_msg_slugs_navigation_get_totalDist(msg); + slugs_navigation->dist2Go = mavlink_msg_slugs_navigation_get_dist2Go(msg); + slugs_navigation->fromWP = mavlink_msg_slugs_navigation_get_fromWP(msg); + slugs_navigation->toWP = mavlink_msg_slugs_navigation_get_toWP(msg); +#else + memcpy(slugs_navigation, _MAV_PAYLOAD(msg), 30); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/slugs.h b/libraries/GCS_MAVLink/include_v1.0/slugs/slugs.h new file mode 100644 index 0000000000..31cde68b0c --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/slugs.h @@ -0,0 +1,62 @@ +/** @file + * @brief MAVLink comm protocol generated from slugs.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef SLUGS_H +#define SLUGS_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 0, 28, 22, 22, 21, 0, 36, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 20, 32, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 10, 24, 18, 0, 0, 30, 24, 0, 7, 13, 3, 0, 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 0, 104, 244, 237, 222, 0, 158, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 160, 168, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 75, 232, 168, 2, 0, 0, 120, 167, 0, 16, 146, 104, 0, 65, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {NULL}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SET_MODE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, {NULL}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, {NULL}, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {NULL}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {NULL}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {NULL}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_SHORT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_CPU_LOAD, MAVLINK_MESSAGE_INFO_AIR_DATA, MAVLINK_MESSAGE_INFO_SENSOR_BIAS, MAVLINK_MESSAGE_INFO_DIAGNOSTIC, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_SLUGS_NAVIGATION, MAVLINK_MESSAGE_INFO_DATA_LOG, {NULL}, MAVLINK_MESSAGE_INFO_GPS_DATE_TIME, MAVLINK_MESSAGE_INFO_MID_LVL_CMDS, MAVLINK_MESSAGE_INFO_CTRL_SRFC_PT, {NULL}, MAVLINK_MESSAGE_INFO_SLUGS_ACTION, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_SLUGS + +#include "../common/common.h" + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 2 +#endif + +// ENUM DEFINITIONS + + + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_cpu_load.h" +#include "./mavlink_msg_air_data.h" +#include "./mavlink_msg_sensor_bias.h" +#include "./mavlink_msg_diagnostic.h" +#include "./mavlink_msg_slugs_navigation.h" +#include "./mavlink_msg_data_log.h" +#include "./mavlink_msg_gps_date_time.h" +#include "./mavlink_msg_mid_lvl_cmds.h" +#include "./mavlink_msg_ctrl_srfc_pt.h" +#include "./mavlink_msg_slugs_action.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // SLUGS_H diff --git a/libraries/GCS_MAVLink/include_v1.0/slugs/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/slugs/testsuite.h new file mode 100644 index 0000000000..4593235a4a --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/slugs/testsuite.h @@ -0,0 +1,552 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from slugs.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef SLUGS_TESTSUITE_H +#define SLUGS_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_slugs(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_slugs(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_cpu_load(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_cpu_load_t packet_in = { + 17235, + 139, + 206, + }; + mavlink_cpu_load_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.batVolt = packet_in.batVolt; + packet1.sensLoad = packet_in.sensLoad; + packet1.ctrlLoad = packet_in.ctrlLoad; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_cpu_load_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_cpu_load_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_cpu_load_pack(system_id, component_id, &msg , packet1.sensLoad , packet1.ctrlLoad , packet1.batVolt ); + mavlink_msg_cpu_load_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_cpu_load_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sensLoad , packet1.ctrlLoad , packet1.batVolt ); + mavlink_msg_cpu_load_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message(msg, system_id, component_id, 179, 103); +} + +/** + * @brief Pack a test_types message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + memcpy(_MAV_PAYLOAD(msg), buf, 179); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + memcpy(packet.d_array, d_array, sizeof(double)*3); + memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + memcpy(packet.f_array, f_array, sizeof(float)*3); + memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + memcpy(packet.s, s, sizeof(char)*10); + memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + memcpy(_MAV_PAYLOAD(msg), &packet, 179); +#endif + + msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179, 103); +} + +/** + * @brief Encode a test_types struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param test_types C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) +{ + return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); +} + +/** + * @brief Send a test_types message + * @param chan MAVLink channel to send the message + * + * @param c char + * @param s string + * @param u8 uint8_t + * @param u16 uint16_t + * @param u32 uint32_t + * @param u64 uint64_t + * @param s8 int8_t + * @param s16 int16_t + * @param s32 int32_t + * @param s64 int64_t + * @param f float + * @param d double + * @param u8_array uint8_t_array + * @param u16_array uint16_t_array + * @param u32_array uint32_t_array + * @param u64_array uint64_t_array + * @param s8_array int8_t_array + * @param s16_array int16_t_array + * @param s32_array int32_t_array + * @param s64_array int64_t_array + * @param f_array float_array + * @param d_array double_array + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[179]; + _mav_put_uint64_t(buf, 0, u64); + _mav_put_int64_t(buf, 8, s64); + _mav_put_double(buf, 16, d); + _mav_put_uint32_t(buf, 96, u32); + _mav_put_int32_t(buf, 100, s32); + _mav_put_float(buf, 104, f); + _mav_put_uint16_t(buf, 144, u16); + _mav_put_int16_t(buf, 146, s16); + _mav_put_char(buf, 160, c); + _mav_put_uint8_t(buf, 171, u8); + _mav_put_int8_t(buf, 172, s8); + _mav_put_uint64_t_array(buf, 24, u64_array, 3); + _mav_put_int64_t_array(buf, 48, s64_array, 3); + _mav_put_double_array(buf, 72, d_array, 3); + _mav_put_uint32_t_array(buf, 108, u32_array, 3); + _mav_put_int32_t_array(buf, 120, s32_array, 3); + _mav_put_float_array(buf, 132, f_array, 3); + _mav_put_uint16_t_array(buf, 148, u16_array, 3); + _mav_put_int16_t_array(buf, 154, s16_array, 3); + _mav_put_char_array(buf, 161, s, 10); + _mav_put_uint8_t_array(buf, 173, u8_array, 3); + _mav_put_int8_t_array(buf, 176, s8_array, 3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103); +#else + mavlink_test_types_t packet; + packet.u64 = u64; + packet.s64 = s64; + packet.d = d; + packet.u32 = u32; + packet.s32 = s32; + packet.f = f; + packet.u16 = u16; + packet.s16 = s16; + packet.c = c; + packet.u8 = u8; + packet.s8 = s8; + memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); + memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); + memcpy(packet.d_array, d_array, sizeof(double)*3); + memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); + memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); + memcpy(packet.f_array, f_array, sizeof(float)*3); + memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); + memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); + memcpy(packet.s, s, sizeof(char)*10); + memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); + memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103); +#endif +} + +#endif + +// MESSAGE TEST_TYPES UNPACKING + + +/** + * @brief Get field c from test_types message + * + * @return char + */ +static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) +{ + return _MAV_RETURN_char(msg, 160); +} + +/** + * @brief Get field s from test_types message + * + * @return string + */ +static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) +{ + return _MAV_RETURN_char_array(msg, s, 10, 161); +} + +/** + * @brief Get field u8 from test_types message + * + * @return uint8_t + */ +static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 171); +} + +/** + * @brief Get field u16 from test_types message + * + * @return uint16_t + */ +static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 144); +} + +/** + * @brief Get field u32 from test_types message + * + * @return uint32_t + */ +static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 96); +} + +/** + * @brief Get field u64 from test_types message + * + * @return uint64_t + */ +static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field s8 from test_types message + * + * @return int8_t + */ +static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int8_t(msg, 172); +} + +/** + * @brief Get field s16 from test_types message + * + * @return int16_t + */ +static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int16_t(msg, 146); +} + +/** + * @brief Get field s32 from test_types message + * + * @return int32_t + */ +static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 100); +} + +/** + * @brief Get field s64 from test_types message + * + * @return int64_t + */ +static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int64_t(msg, 8); +} + +/** + * @brief Get field f from test_types message + * + * @return float + */ +static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 104); +} + +/** + * @brief Get field d from test_types message + * + * @return double + */ +static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) +{ + return _MAV_RETURN_double(msg, 16); +} + +/** + * @brief Get field u8_array from test_types message + * + * @return uint8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) +{ + return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173); +} + +/** + * @brief Get field u16_array from test_types message + * + * @return uint16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) +{ + return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148); +} + +/** + * @brief Get field u32_array from test_types message + * + * @return uint32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) +{ + return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108); +} + +/** + * @brief Get field u64_array from test_types message + * + * @return uint64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) +{ + return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24); +} + +/** + * @brief Get field s8_array from test_types message + * + * @return int8_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) +{ + return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176); +} + +/** + * @brief Get field s16_array from test_types message + * + * @return int16_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) +{ + return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154); +} + +/** + * @brief Get field s32_array from test_types message + * + * @return int32_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) +{ + return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120); +} + +/** + * @brief Get field s64_array from test_types message + * + * @return int64_t_array + */ +static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) +{ + return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48); +} + +/** + * @brief Get field f_array from test_types message + * + * @return float_array + */ +static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) +{ + return _MAV_RETURN_float_array(msg, f_array, 3, 132); +} + +/** + * @brief Get field d_array from test_types message + * + * @return double_array + */ +static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) +{ + return _MAV_RETURN_double_array(msg, d_array, 3, 72); +} + +/** + * @brief Decode a test_types message into a struct + * + * @param msg The message to decode + * @param test_types C-struct to decode the message contents into + */ +static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) +{ +#if MAVLINK_NEED_BYTE_SWAP + test_types->u64 = mavlink_msg_test_types_get_u64(msg); + test_types->s64 = mavlink_msg_test_types_get_s64(msg); + test_types->d = mavlink_msg_test_types_get_d(msg); + mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); + mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); + mavlink_msg_test_types_get_d_array(msg, test_types->d_array); + test_types->u32 = mavlink_msg_test_types_get_u32(msg); + test_types->s32 = mavlink_msg_test_types_get_s32(msg); + test_types->f = mavlink_msg_test_types_get_f(msg); + mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); + mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); + mavlink_msg_test_types_get_f_array(msg, test_types->f_array); + test_types->u16 = mavlink_msg_test_types_get_u16(msg); + test_types->s16 = mavlink_msg_test_types_get_s16(msg); + mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); + mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); + test_types->c = mavlink_msg_test_types_get_c(msg); + mavlink_msg_test_types_get_s(msg, test_types->s); + test_types->u8 = mavlink_msg_test_types_get_u8(msg); + test_types->s8 = mavlink_msg_test_types_get_s8(msg); + mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); + mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); +#else + memcpy(test_types, _MAV_PAYLOAD(msg), 179); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/test/test.h b/libraries/GCS_MAVLink/include_v1.0/test/test.h new file mode 100644 index 0000000000..4dc04f889f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/test/test.h @@ -0,0 +1,53 @@ +/** @file + * @brief MAVLink comm protocol generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_H +#define TEST_H + +#ifdef __cplusplus +extern "C" { +#endif + +// MESSAGE LENGTHS AND CRCS + +#ifndef MAVLINK_MESSAGE_LENGTHS +#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_CRCS +#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} +#endif + +#ifndef MAVLINK_MESSAGE_INFO +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}} +#endif + +#include "../protocol.h" + +#define MAVLINK_ENABLED_TEST + + + +// MAVLINK VERSION + +#ifndef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +#if (MAVLINK_VERSION == 0) +#undef MAVLINK_VERSION +#define MAVLINK_VERSION 3 +#endif + +// ENUM DEFINITIONS + + + +// MESSAGE DEFINITIONS +#include "./mavlink_msg_test_types.h" + +#ifdef __cplusplus +} +#endif // __cplusplus +#endif // TEST_H diff --git a/libraries/GCS_MAVLink/include_v1.0/test/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/test/testsuite.h new file mode 100644 index 0000000000..bfb269fb5f --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/test/testsuite.h @@ -0,0 +1,120 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from test.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef TEST_TESTSUITE_H +#define TEST_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL + +static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + + mavlink_test_test(system_id, component_id, last_msg); +} +#endif + + + + +static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_test_types_t packet_in = { + 93372036854775807ULL, + 93372036854776311LL, + 235.0, + { 93372036854777319, 93372036854777320, 93372036854777321 }, + { 93372036854778831, 93372036854778832, 93372036854778833 }, + { 627.0, 628.0, 629.0 }, + 963502456, + 963502664, + 745.0, + { 963503080, 963503081, 963503082 }, + { 963503704, 963503705, 963503706 }, + { 941.0, 942.0, 943.0 }, + 24723, + 24827, + { 24931, 24932, 24933 }, + { 25243, 25244, 25245 }, + 'E', + "FGHIJKLMN", + 198, + 9, + { 76, 77, 78 }, + { 21, 22, 23 }, + }; + mavlink_test_types_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.u64 = packet_in.u64; + packet1.s64 = packet_in.s64; + packet1.d = packet_in.d; + packet1.u32 = packet_in.u32; + packet1.s32 = packet_in.s32; + packet1.f = packet_in.f; + packet1.u16 = packet_in.u16; + packet1.s16 = packet_in.s16; + packet1.c = packet_in.c; + packet1.u8 = packet_in.u8; + packet1.s8 = packet_in.s8; + + memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); + memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); + memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); + memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); + memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); + memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); + memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); + memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); + memcpy(packet1.s, packet_in.s, sizeof(char)*10); + memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); + memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); + mavlink_msg_test_types_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; imsgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; + return mavlink_finalize_message(msg, system_id, component_id, 32, 34); +} + +/** + * @brief Pack a nav_filter_bias message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_nav_filter_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t usec,float accel_0,float accel_1,float accel_2,float gyro_0,float gyro_1,float gyro_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, accel_0); + _mav_put_float(buf, 12, accel_1); + _mav_put_float(buf, 16, accel_2); + _mav_put_float(buf, 20, gyro_0); + _mav_put_float(buf, 24, gyro_1); + _mav_put_float(buf, 28, gyro_2); + + memcpy(_MAV_PAYLOAD(msg), buf, 32); +#else + mavlink_nav_filter_bias_t packet; + packet.usec = usec; + packet.accel_0 = accel_0; + packet.accel_1 = accel_1; + packet.accel_2 = accel_2; + packet.gyro_0 = gyro_0; + packet.gyro_1 = gyro_1; + packet.gyro_2 = gyro_2; + + memcpy(_MAV_PAYLOAD(msg), &packet, 32); +#endif + + msg->msgid = MAVLINK_MSG_ID_NAV_FILTER_BIAS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 34); +} + +/** + * @brief Encode a nav_filter_bias struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param nav_filter_bias C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_nav_filter_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_filter_bias_t* nav_filter_bias) +{ + return mavlink_msg_nav_filter_bias_pack(system_id, component_id, msg, nav_filter_bias->usec, nav_filter_bias->accel_0, nav_filter_bias->accel_1, nav_filter_bias->accel_2, nav_filter_bias->gyro_0, nav_filter_bias->gyro_1, nav_filter_bias->gyro_2); +} + +/** + * @brief Send a nav_filter_bias message + * @param chan MAVLink channel to send the message + * + * @param usec Timestamp (microseconds) + * @param accel_0 b_f[0] + * @param accel_1 b_f[1] + * @param accel_2 b_f[2] + * @param gyro_0 b_f[0] + * @param gyro_1 b_f[1] + * @param gyro_2 b_f[2] + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_nav_filter_bias_send(mavlink_channel_t chan, uint64_t usec, float accel_0, float accel_1, float accel_2, float gyro_0, float gyro_1, float gyro_2) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[32]; + _mav_put_uint64_t(buf, 0, usec); + _mav_put_float(buf, 8, accel_0); + _mav_put_float(buf, 12, accel_1); + _mav_put_float(buf, 16, accel_2); + _mav_put_float(buf, 20, gyro_0); + _mav_put_float(buf, 24, gyro_1); + _mav_put_float(buf, 28, gyro_2); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_FILTER_BIAS, buf, 32, 34); +#else + mavlink_nav_filter_bias_t packet; + packet.usec = usec; + packet.accel_0 = accel_0; + packet.accel_1 = accel_1; + packet.accel_2 = accel_2; + packet.gyro_0 = gyro_0; + packet.gyro_1 = gyro_1; + packet.gyro_2 = gyro_2; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_FILTER_BIAS, (const char *)&packet, 32, 34); +#endif +} + +#endif + +// MESSAGE NAV_FILTER_BIAS UNPACKING + + +/** + * @brief Get field usec from nav_filter_bias message + * + * @return Timestamp (microseconds) + */ +static inline uint64_t mavlink_msg_nav_filter_bias_get_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field accel_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field accel_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field accel_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_accel_2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field gyro_0 from nav_filter_bias message + * + * @return b_f[0] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_0(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field gyro_1 from nav_filter_bias message + * + * @return b_f[1] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field gyro_2 from nav_filter_bias message + * + * @return b_f[2] + */ +static inline float mavlink_msg_nav_filter_bias_get_gyro_2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Decode a nav_filter_bias message into a struct + * + * @param msg The message to decode + * @param nav_filter_bias C-struct to decode the message contents into + */ +static inline void mavlink_msg_nav_filter_bias_decode(const mavlink_message_t* msg, mavlink_nav_filter_bias_t* nav_filter_bias) +{ +#if MAVLINK_NEED_BYTE_SWAP + nav_filter_bias->usec = mavlink_msg_nav_filter_bias_get_usec(msg); + nav_filter_bias->accel_0 = mavlink_msg_nav_filter_bias_get_accel_0(msg); + nav_filter_bias->accel_1 = mavlink_msg_nav_filter_bias_get_accel_1(msg); + nav_filter_bias->accel_2 = mavlink_msg_nav_filter_bias_get_accel_2(msg); + nav_filter_bias->gyro_0 = mavlink_msg_nav_filter_bias_get_gyro_0(msg); + nav_filter_bias->gyro_1 = mavlink_msg_nav_filter_bias_get_gyro_1(msg); + nav_filter_bias->gyro_2 = mavlink_msg_nav_filter_bias_get_gyro_2(msg); +#else + memcpy(nav_filter_bias, _MAV_PAYLOAD(msg), 32); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_radio_calibration.h b/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_radio_calibration.h new file mode 100644 index 0000000000..ffe2b74856 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_radio_calibration.h @@ -0,0 +1,259 @@ +// MESSAGE RADIO_CALIBRATION PACKING + +#define MAVLINK_MSG_ID_RADIO_CALIBRATION 221 + +typedef struct __mavlink_radio_calibration_t +{ + uint16_t aileron[3]; ///< Aileron setpoints: left, center, right + uint16_t elevator[3]; ///< Elevator setpoints: nose down, center, nose up + uint16_t rudder[3]; ///< Rudder setpoints: nose left, center, nose right + uint16_t gyro[2]; ///< Tail gyro mode/gain setpoints: heading hold, rate mode + uint16_t pitch[5]; ///< Pitch curve setpoints (every 25%) + uint16_t throttle[5]; ///< Throttle curve setpoints (every 25%) +} mavlink_radio_calibration_t; + +#define MAVLINK_MSG_ID_RADIO_CALIBRATION_LEN 42 +#define MAVLINK_MSG_ID_221_LEN 42 + +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN 3 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN 2 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN 5 +#define MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN 5 + +#define MAVLINK_MESSAGE_INFO_RADIO_CALIBRATION { \ + "RADIO_CALIBRATION", \ + 6, \ + { { "aileron", NULL, MAVLINK_TYPE_UINT16_T, 3, 0, offsetof(mavlink_radio_calibration_t, aileron) }, \ + { "elevator", NULL, MAVLINK_TYPE_UINT16_T, 3, 6, offsetof(mavlink_radio_calibration_t, elevator) }, \ + { "rudder", NULL, MAVLINK_TYPE_UINT16_T, 3, 12, offsetof(mavlink_radio_calibration_t, rudder) }, \ + { "gyro", NULL, MAVLINK_TYPE_UINT16_T, 2, 18, offsetof(mavlink_radio_calibration_t, gyro) }, \ + { "pitch", NULL, MAVLINK_TYPE_UINT16_T, 5, 22, offsetof(mavlink_radio_calibration_t, pitch) }, \ + { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 5, 32, offsetof(mavlink_radio_calibration_t, throttle) }, \ + } \ +} + + +/** + * @brief Pack a radio_calibration message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_calibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + const uint16_t *aileron, const uint16_t *elevator, const uint16_t *rudder, const uint16_t *gyro, const uint16_t *pitch, const uint16_t *throttle) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + + _mav_put_uint16_t_array(buf, 0, aileron, 3); + _mav_put_uint16_t_array(buf, 6, elevator, 3); + _mav_put_uint16_t_array(buf, 12, rudder, 3); + _mav_put_uint16_t_array(buf, 18, gyro, 2); + _mav_put_uint16_t_array(buf, 22, pitch, 5); + _mav_put_uint16_t_array(buf, 32, throttle, 5); + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_radio_calibration_t packet; + + memcpy(packet.aileron, aileron, sizeof(uint16_t)*3); + memcpy(packet.elevator, elevator, sizeof(uint16_t)*3); + memcpy(packet.rudder, rudder, sizeof(uint16_t)*3); + memcpy(packet.gyro, gyro, sizeof(uint16_t)*2); + memcpy(packet.pitch, pitch, sizeof(uint16_t)*5); + memcpy(packet.throttle, throttle, sizeof(uint16_t)*5); + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; + return mavlink_finalize_message(msg, system_id, component_id, 42, 71); +} + +/** + * @brief Pack a radio_calibration message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_radio_calibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + const uint16_t *aileron,const uint16_t *elevator,const uint16_t *rudder,const uint16_t *gyro,const uint16_t *pitch,const uint16_t *throttle) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + + _mav_put_uint16_t_array(buf, 0, aileron, 3); + _mav_put_uint16_t_array(buf, 6, elevator, 3); + _mav_put_uint16_t_array(buf, 12, rudder, 3); + _mav_put_uint16_t_array(buf, 18, gyro, 2); + _mav_put_uint16_t_array(buf, 22, pitch, 5); + _mav_put_uint16_t_array(buf, 32, throttle, 5); + memcpy(_MAV_PAYLOAD(msg), buf, 42); +#else + mavlink_radio_calibration_t packet; + + memcpy(packet.aileron, aileron, sizeof(uint16_t)*3); + memcpy(packet.elevator, elevator, sizeof(uint16_t)*3); + memcpy(packet.rudder, rudder, sizeof(uint16_t)*3); + memcpy(packet.gyro, gyro, sizeof(uint16_t)*2); + memcpy(packet.pitch, pitch, sizeof(uint16_t)*5); + memcpy(packet.throttle, throttle, sizeof(uint16_t)*5); + memcpy(_MAV_PAYLOAD(msg), &packet, 42); +#endif + + msg->msgid = MAVLINK_MSG_ID_RADIO_CALIBRATION; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 71); +} + +/** + * @brief Encode a radio_calibration struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param radio_calibration C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_radio_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_calibration_t* radio_calibration) +{ + return mavlink_msg_radio_calibration_pack(system_id, component_id, msg, radio_calibration->aileron, radio_calibration->elevator, radio_calibration->rudder, radio_calibration->gyro, radio_calibration->pitch, radio_calibration->throttle); +} + +/** + * @brief Send a radio_calibration message + * @param chan MAVLink channel to send the message + * + * @param aileron Aileron setpoints: left, center, right + * @param elevator Elevator setpoints: nose down, center, nose up + * @param rudder Rudder setpoints: nose left, center, nose right + * @param gyro Tail gyro mode/gain setpoints: heading hold, rate mode + * @param pitch Pitch curve setpoints (every 25%) + * @param throttle Throttle curve setpoints (every 25%) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_radio_calibration_send(mavlink_channel_t chan, const uint16_t *aileron, const uint16_t *elevator, const uint16_t *rudder, const uint16_t *gyro, const uint16_t *pitch, const uint16_t *throttle) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[42]; + + _mav_put_uint16_t_array(buf, 0, aileron, 3); + _mav_put_uint16_t_array(buf, 6, elevator, 3); + _mav_put_uint16_t_array(buf, 12, rudder, 3); + _mav_put_uint16_t_array(buf, 18, gyro, 2); + _mav_put_uint16_t_array(buf, 22, pitch, 5); + _mav_put_uint16_t_array(buf, 32, throttle, 5); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, buf, 42, 71); +#else + mavlink_radio_calibration_t packet; + + memcpy(packet.aileron, aileron, sizeof(uint16_t)*3); + memcpy(packet.elevator, elevator, sizeof(uint16_t)*3); + memcpy(packet.rudder, rudder, sizeof(uint16_t)*3); + memcpy(packet.gyro, gyro, sizeof(uint16_t)*2); + memcpy(packet.pitch, pitch, sizeof(uint16_t)*5); + memcpy(packet.throttle, throttle, sizeof(uint16_t)*5); + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_CALIBRATION, (const char *)&packet, 42, 71); +#endif +} + +#endif + +// MESSAGE RADIO_CALIBRATION UNPACKING + + +/** + * @brief Get field aileron from radio_calibration message + * + * @return Aileron setpoints: left, center, right + */ +static inline uint16_t mavlink_msg_radio_calibration_get_aileron(const mavlink_message_t* msg, uint16_t *aileron) +{ + return _MAV_RETURN_uint16_t_array(msg, aileron, 3, 0); +} + +/** + * @brief Get field elevator from radio_calibration message + * + * @return Elevator setpoints: nose down, center, nose up + */ +static inline uint16_t mavlink_msg_radio_calibration_get_elevator(const mavlink_message_t* msg, uint16_t *elevator) +{ + return _MAV_RETURN_uint16_t_array(msg, elevator, 3, 6); +} + +/** + * @brief Get field rudder from radio_calibration message + * + * @return Rudder setpoints: nose left, center, nose right + */ +static inline uint16_t mavlink_msg_radio_calibration_get_rudder(const mavlink_message_t* msg, uint16_t *rudder) +{ + return _MAV_RETURN_uint16_t_array(msg, rudder, 3, 12); +} + +/** + * @brief Get field gyro from radio_calibration message + * + * @return Tail gyro mode/gain setpoints: heading hold, rate mode + */ +static inline uint16_t mavlink_msg_radio_calibration_get_gyro(const mavlink_message_t* msg, uint16_t *gyro) +{ + return _MAV_RETURN_uint16_t_array(msg, gyro, 2, 18); +} + +/** + * @brief Get field pitch from radio_calibration message + * + * @return Pitch curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_pitch(const mavlink_message_t* msg, uint16_t *pitch) +{ + return _MAV_RETURN_uint16_t_array(msg, pitch, 5, 22); +} + +/** + * @brief Get field throttle from radio_calibration message + * + * @return Throttle curve setpoints (every 25%) + */ +static inline uint16_t mavlink_msg_radio_calibration_get_throttle(const mavlink_message_t* msg, uint16_t *throttle) +{ + return _MAV_RETURN_uint16_t_array(msg, throttle, 5, 32); +} + +/** + * @brief Decode a radio_calibration message into a struct + * + * @param msg The message to decode + * @param radio_calibration C-struct to decode the message contents into + */ +static inline void mavlink_msg_radio_calibration_decode(const mavlink_message_t* msg, mavlink_radio_calibration_t* radio_calibration) +{ +#if MAVLINK_NEED_BYTE_SWAP + mavlink_msg_radio_calibration_get_aileron(msg, radio_calibration->aileron); + mavlink_msg_radio_calibration_get_elevator(msg, radio_calibration->elevator); + mavlink_msg_radio_calibration_get_rudder(msg, radio_calibration->rudder); + mavlink_msg_radio_calibration_get_gyro(msg, radio_calibration->gyro); + mavlink_msg_radio_calibration_get_pitch(msg, radio_calibration->pitch); + mavlink_msg_radio_calibration_get_throttle(msg, radio_calibration->throttle); +#else + memcpy(radio_calibration, _MAV_PAYLOAD(msg), 42); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_ualberta_sys_status.h b/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_ualberta_sys_status.h new file mode 100644 index 0000000000..69c4599e13 --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ualberta/mavlink_msg_ualberta_sys_status.h @@ -0,0 +1,188 @@ +// MESSAGE UALBERTA_SYS_STATUS PACKING + +#define MAVLINK_MSG_ID_UALBERTA_SYS_STATUS 222 + +typedef struct __mavlink_ualberta_sys_status_t +{ + uint8_t mode; ///< System mode, see UALBERTA_AUTOPILOT_MODE ENUM + uint8_t nav_mode; ///< Navigation mode, see UALBERTA_NAV_MODE ENUM + uint8_t pilot; ///< Pilot mode, see UALBERTA_PILOT_MODE +} mavlink_ualberta_sys_status_t; + +#define MAVLINK_MSG_ID_UALBERTA_SYS_STATUS_LEN 3 +#define MAVLINK_MSG_ID_222_LEN 3 + + + +#define MAVLINK_MESSAGE_INFO_UALBERTA_SYS_STATUS { \ + "UALBERTA_SYS_STATUS", \ + 3, \ + { { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_ualberta_sys_status_t, mode) }, \ + { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_ualberta_sys_status_t, nav_mode) }, \ + { "pilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_ualberta_sys_status_t, pilot) }, \ + } \ +} + + +/** + * @brief Pack a ualberta_sys_status message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint8_t mode, uint8_t nav_mode, uint8_t pilot) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, mode); + _mav_put_uint8_t(buf, 1, nav_mode); + _mav_put_uint8_t(buf, 2, pilot); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_ualberta_sys_status_t packet; + packet.mode = mode; + packet.nav_mode = nav_mode; + packet.pilot = pilot; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; + return mavlink_finalize_message(msg, system_id, component_id, 3, 15); +} + +/** + * @brief Pack a ualberta_sys_status message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message was sent over + * @param msg The MAVLink message to compress the data into + * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint8_t mode,uint8_t nav_mode,uint8_t pilot) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, mode); + _mav_put_uint8_t(buf, 1, nav_mode); + _mav_put_uint8_t(buf, 2, pilot); + + memcpy(_MAV_PAYLOAD(msg), buf, 3); +#else + mavlink_ualberta_sys_status_t packet; + packet.mode = mode; + packet.nav_mode = nav_mode; + packet.pilot = pilot; + + memcpy(_MAV_PAYLOAD(msg), &packet, 3); +#endif + + msg->msgid = MAVLINK_MSG_ID_UALBERTA_SYS_STATUS; + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 15); +} + +/** + * @brief Encode a ualberta_sys_status struct into a message + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param ualberta_sys_status C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_ualberta_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ualberta_sys_status_t* ualberta_sys_status) +{ + return mavlink_msg_ualberta_sys_status_pack(system_id, component_id, msg, ualberta_sys_status->mode, ualberta_sys_status->nav_mode, ualberta_sys_status->pilot); +} + +/** + * @brief Send a ualberta_sys_status message + * @param chan MAVLink channel to send the message + * + * @param mode System mode, see UALBERTA_AUTOPILOT_MODE ENUM + * @param nav_mode Navigation mode, see UALBERTA_NAV_MODE ENUM + * @param pilot Pilot mode, see UALBERTA_PILOT_MODE + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_ualberta_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t pilot) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[3]; + _mav_put_uint8_t(buf, 0, mode); + _mav_put_uint8_t(buf, 1, nav_mode); + _mav_put_uint8_t(buf, 2, pilot); + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UALBERTA_SYS_STATUS, buf, 3, 15); +#else + mavlink_ualberta_sys_status_t packet; + packet.mode = mode; + packet.nav_mode = nav_mode; + packet.pilot = pilot; + + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UALBERTA_SYS_STATUS, (const char *)&packet, 3, 15); +#endif +} + +#endif + +// MESSAGE UALBERTA_SYS_STATUS UNPACKING + + +/** + * @brief Get field mode from ualberta_sys_status message + * + * @return System mode, see UALBERTA_AUTOPILOT_MODE ENUM + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 0); +} + +/** + * @brief Get field nav_mode from ualberta_sys_status message + * + * @return Navigation mode, see UALBERTA_NAV_MODE ENUM + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_nav_mode(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 1); +} + +/** + * @brief Get field pilot from ualberta_sys_status message + * + * @return Pilot mode, see UALBERTA_PILOT_MODE + */ +static inline uint8_t mavlink_msg_ualberta_sys_status_get_pilot(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 2); +} + +/** + * @brief Decode a ualberta_sys_status message into a struct + * + * @param msg The message to decode + * @param ualberta_sys_status C-struct to decode the message contents into + */ +static inline void mavlink_msg_ualberta_sys_status_decode(const mavlink_message_t* msg, mavlink_ualberta_sys_status_t* ualberta_sys_status) +{ +#if MAVLINK_NEED_BYTE_SWAP + ualberta_sys_status->mode = mavlink_msg_ualberta_sys_status_get_mode(msg); + ualberta_sys_status->nav_mode = mavlink_msg_ualberta_sys_status_get_nav_mode(msg); + ualberta_sys_status->pilot = mavlink_msg_ualberta_sys_status_get_pilot(msg); +#else + memcpy(ualberta_sys_status, _MAV_PAYLOAD(msg), 3); +#endif +} diff --git a/libraries/GCS_MAVLink/include_v1.0/ualberta/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/ualberta/testsuite.h new file mode 100644 index 0000000000..11ba27a3cf --- /dev/null +++ b/libraries/GCS_MAVLink/include_v1.0/ualberta/testsuite.h @@ -0,0 +1,192 @@ +/** @file + * @brief MAVLink comm protocol testsuite generated from ualberta.xml + * @see http://qgroundcontrol.org/mavlink/ + */ +#ifndef UALBERTA_TESTSUITE_H +#define UALBERTA_TESTSUITE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef MAVLINK_TEST_ALL +#define MAVLINK_TEST_ALL +static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); +static void mavlink_test_ualberta(uint8_t, uint8_t, mavlink_message_t *last_msg); + +static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_test_common(system_id, component_id, last_msg); + mavlink_test_ualberta(system_id, component_id, last_msg); +} +#endif + +#include "../common/testsuite.h" + + +static void mavlink_test_nav_filter_bias(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_nav_filter_bias_t packet_in = { + 93372036854775807ULL, + 73.0, + 101.0, + 129.0, + 157.0, + 185.0, + 213.0, + }; + mavlink_nav_filter_bias_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.usec = packet_in.usec; + packet1.accel_0 = packet_in.accel_0; + packet1.accel_1 = packet_in.accel_1; + packet1.accel_2 = packet_in.accel_2; + packet1.gyro_0 = packet_in.gyro_0; + packet1.gyro_1 = packet_in.gyro_1; + packet1.gyro_2 = packet_in.gyro_2; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_nav_filter_bias_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_nav_filter_bias_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_nav_filter_bias_pack(system_id, component_id, &msg , packet1.usec , packet1.accel_0 , packet1.accel_1 , packet1.accel_2 , packet1.gyro_0 , packet1.gyro_1 , packet1.gyro_2 ); + mavlink_msg_nav_filter_bias_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_nav_filter_bias_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.accel_0 , packet1.accel_1 , packet1.accel_2 , packet1.gyro_0 , packet1.gyro_1 , packet1.gyro_2 ); + mavlink_msg_nav_filter_bias_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; ifree memory + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + diff --git a/libraries/GCS_MAVLink/message_definitions/test.xml b/libraries/GCS_MAVLink/message_definitions/test.xml new file mode 100644 index 0000000000..43a11e3d13 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml new file mode 100644 index 0000000000..33fc5b8de5 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml @@ -0,0 +1,55 @@ + + + common.xml + + + + Offsets and calibrations values for hardware + sensors. This makes it easier to debug the calibration process. + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + magnetic declination (radians) + raw pressure from barometer + raw temperature from barometer + gyro X calibration + gyro Y calibration + gyro Z calibration + accel X calibration + accel Y calibration + accel Z calibration + + + + set the magnetometer offsets + System ID + Component ID + magnetometer X offset + magnetometer Y offset + magnetometer Z offset + + + + state of APM memory + heap top + free memory + + + + raw ADC output + ADC output 1 + ADC output 2 + ADC output 3 + ADC output 4 + ADC output 5 + ADC output 6 + + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml new file mode 100644 index 0000000000..066d2dbc78 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml @@ -0,0 +1,1433 @@ + + + 3 + + + Micro air vehicle / autopilot classes. This identifies the individual model. + + Generic autopilot, full support for everything + + + PIXHAWK autopilot, http://pixhawk.ethz.ch + + + SLUGS autopilot, http://slugsuav.soe.ucsc.edu + + + ArduPilotMega / ArduCopter, http://diydrones.com + + + OpenPilot, http://openpilot.org + + + Generic autopilot only supporting simple waypoints + + + Generic autopilot supporting waypoints and other simple navigation commands + + + Generic autopilot supporting the full mission command set + + + No valid autopilot, e.g. a GCS or other MAVLink component + + + PPZ UAV - http://nongnu.org/paparazzi + + + UAV Dev Board + + + FlexiPilot + + + + + These flags encode the MAV mode. + + 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. + + + 0b01000000 remote control input is enabled. + + + 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. + + + 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. + + + 0b00001000 guided mode enabled, system flies MISSIONs / mission items. + + + 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. + + + 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. + + + 0b00000001 Reserved for future use. + + + + + These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. + + First bit: 10000000 + + + Second bit: 01000000 + + + Third bit: 00100000 + + + Fourth bit: 00010000 + + + Fifth bit: 00001000 + + + Sixt bit: 00000100 + + + Seventh bit: 00000010 + + + Eighth bit: 00000001 + + + + Override command, pauses current mission execution and moves immediately to a position + + Hold at the current position. + + + Continue with the mission execution. + + + Hold at the current position of the system + + + Hold at the position specified in the parameters of the DO_HOLD action + + + + These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. + + System is not ready to fly, booting, calibrating, etc. No flag is set. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under assisted RC control. + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under manual (RC) control, no stabilization + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control, manual setpoint + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. + + + + + Uninitialized system, state is unknown. + + + System is booting up. + + + System is calibrating and not flight-ready. + + + System is grounded and on standby. It can be launched any time. + + + System is active and might be already airborne. Motors are engaged. + + + System is in a non-normal flight mode. It can however still navigate. + + + System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. + + + System just initialized its power-down sequence, will shut down now. + + + + + Generic micro air vehicle. + + + Fixed wing aircraft. + + + Quadrotor + + + Coaxial helicopter + + + Normal helicopter with tail rotor. + + + Ground installation + + + Operator control unit / ground control station + + + Airship, controlled + + + Free balloon, uncontrolled + + + Rocket + + + Ground rover + + + Surface vessel, boat, ship + + + Submarine + + + Hexarotor + + + Octorotor + + + Octorotor + + + Flapping wing + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) + + + Local coordinate frame, Z-up (x: north, y: east, z: down). + + + NOT a coordinate frame, indicates a mission command. + + + Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. + + + Local coordinate frame, Z-down (x: east, y: north, z: up) + + + + + + + + + + + + + + + + + + + + + + + + Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. + + Navigate to MISSION. + Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing) + Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached) + 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. + Desired yaw angle at MISSION (rotary wing) + Latitude + Longitude + Altitude + + + Loiter around this MISSION an unlimited amount of time + Empty + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X turns + Turns + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Loiter around this MISSION for X seconds + Seconds (decimal) + Empty + Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise + Desired yaw angle. + Latitude + Longitude + Altitude + + + Return to launch location + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Land at location + Empty + Empty + Empty + Desired yaw angle. + Latitude + Longitude + Altitude + + + Takeoff from ground / hand + Minimum pitch (if airspeed sensor present), desired pitch without sensor + Empty + Empty + Yaw angle (if magnetometer present), ignored without magnetometer + Latitude + Longitude + Altitude + + + Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras. + Region of intereset mode. (see MAV_ROI enum) + MISSION index/ target ID. (see MAV_ROI enum) + ROI index (allows a vehicle to manage multiple ROI's) + Empty + x the location of the fixed ROI (see MAV_FRAME) + y + z + + + Control autonomous path planning on the MAV. + 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning + 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid + Empty + Yaw angle at goal, in compass degrees, [0..360] + Latitude/X of goal + Longitude/Y of goal + Altitude/Z of goal + + + NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Delay mission state machine. + Delay in seconds (decimal) + Empty + Empty + Empty + Empty + Empty + Empty + + + Ascend/descend at rate. Delay mission state machine until desired altitude reached. + Descent / Ascend rate (m/s) + Empty + Empty + Empty + Empty + Empty + Finish Altitude + + + Delay mission state machine until within desired distance of next NAV point. + Distance (meters) + Empty + Empty + Empty + Empty + Empty + Empty + + + Reach a certain target angle. + target angle: [0-360], 0 is north + speed during yaw change:[deg per second] + direction: negative: counter clockwise, positive: clockwise [-1,1] + relative offset or absolute angle: [ 1,0] + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Set system mode. + Mode, as defined by ENUM MAV_MODE + Empty + Empty + Empty + Empty + Empty + Empty + + + Jump to the desired command in the mission list. Repeat this action only the specified number of times + Sequence number + Repeat count + Empty + Empty + Empty + Empty + Empty + + + Change speed and/or throttle set points. + Speed type (0=Airspeed, 1=Ground Speed) + Speed (m/s, -1 indicates no change) + Throttle ( Percent, -1 indicates no change) + Empty + Empty + Empty + Empty + + + Changes the home location either to the current location or a specified location. + Use current (1=use current location, 0=use specified location) + Empty + Empty + Empty + Latitude + Longitude + Altitude + + + Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + Parameter number + Parameter value + Empty + Empty + Empty + Empty + Empty + + + Set a relay to a condition. + Relay number + Setting (1=on, 0=off, others possible depending on system hardware) + Empty + Empty + Empty + Empty + Empty + + + Cycle a relay on and off for a desired number of cyles with a desired period. + Relay number + Cycle count + Cycle time (seconds, decimal) + Empty + Empty + Empty + Empty + + + Set a servo to a desired PWM value. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Empty + Empty + Empty + Empty + Empty + + + Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + Servo number + PWM (microseconds, 1000 to 2000 typical) + Cycle count + Cycle time (seconds) + Empty + Empty + Empty + + + Control onboard camera system. + Camera ID (-1 for all) + Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw + Transmission mode: 0: video stream, >0: single images every n seconds (decimal) + Recording: 0: disabled, 1: enabled compressed, 2: enabled raw + Empty + Empty + Empty + + + NOP - This command is only used to mark the upper limit of the DO commands in the enumeration + Empty + Empty + Empty + Empty + Empty + Empty + Empty + + + Trigger calibration. This command will be only accepted if in pre-flight mode. + Gyro calibration: 0: no, 1: yes + Magnetometer calibration: 0: no, 1: yes + Ground pressure: 0: no, 1: yes + Radio calibration: 0: no, 1: yes + Empty + Empty + Empty + + + Set sensor offsets. This command will be only accepted if in pre-flight mode. + Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow + X axis offset (or generic dimension 1), in the sensor's raw units + Y axis offset (or generic dimension 2), in the sensor's raw units + Z axis offset (or generic dimension 3), in the sensor's raw units + Generic dimension 4, in the sensor's raw units + Generic dimension 5, in the sensor's raw units + Generic dimension 6, in the sensor's raw units + + + Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM + Reserved + Reserved + Empty + Empty + Empty + + + Request the reboot or shutdown of system components. + 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot. + 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer. + Reserved + Reserved + Empty + Empty + Empty + + + Hold / continue the current action + MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with mission plan + MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position + MAV_FRAME coordinate frame of hold point + Desired yaw angle in degrees + Latitude / X position + Longitude / Y position + Altitude / Z position + + + + Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + + + Enable all data streams + + + Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. + + + Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS + + + Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW + + + Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. + + + Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. + + + Dependent on the autopilot + + + Dependent on the autopilot + + + Dependent on the autopilot + + + + The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + + + No region of interest. + + + Point toward next MISSION. + + + Point toward given MISSION. + + + Point toward fixed location. + + + Point toward of given id. + + + + ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. + + Command / mission item is ok. + + + Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. + + + The system is refusing to accept this command from this source / communication partner. + + + Command or mission item is not supported, other commands would be accepted. + + + The coordinate frame of this command / mission item is not supported. + + + The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. + + + The X or latitude value is out of range. + + + The Y or longitude value is out of range. + + + The Z or altitude value is out of range. + + + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_CLASS ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + System status flag, see MAV_STATUS ENUM + MAVLink version + + + The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout. + Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control + Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + Battery voltage, in millivolts (1 = 1 millivolt) + Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current + Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery + Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + Autopilot-specific errors + + + + The system time is the time of the master clock, typically the computer clock of the main onboard computer. + Timestamp of the master clock in microseconds since UNIX epoch. + Timestamp of the component clock since boot time in milliseconds. + + + + A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. + Unix timestamp in microseconds + PING sequence + 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system + 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system + + + Request to control this MAV + System the GCS requests control for + 0: request control of this MAV, 1: Release control of this MAV + 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. + Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" + + + Accept / deny control of this MAV + ID of the GCS this message + 0: request control of this MAV, 1: Release control of this MAV + 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + + + Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety. + key + + + Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component. + The system setting the mode + The new base mode + The new autopilot-specific mode. This field can be ignored by an autopilot. + + + Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code. + System ID + Component ID + Onboard parameter id + Parameter index. Send -1 to use the param ID field as identifier + + + Request all parameters of this component. After his request, all parameters are emitted. + System ID + Component ID + + + Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. + Onboard parameter id + Onboard parameter value + Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + Total number of onboard parameters + Index of this onboard parameter + + + Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message. + System ID + Component ID + Onboard parameter id + Onboard parameter value + Onboard parameter type: 0: float, 1: uint8_t, 2: int8_t, 3: uint16_t, 4: int16_t, 5: uint32_t, 6: int32_t + + + The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame) + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + Latitude in 1E7 degrees + Longitude in 1E7 degrees + Altitude in 1E3 meters (millimeters) above MSL + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites. + Number of satellites visible + Global satellite ID + 0: Satellite not used, 1: used for localization + Elevation (0: right on top of receiver, 90: on the horizon) of satellite + Direction of satellite, 0: 0 deg, 255: 360 deg. + Signal to noise ratio of satellite + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units + Timestamp (milliseconds since system boot) + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Angular speed around X axis (millirad /sec) + Angular speed around Y axis (millirad /sec) + Angular speed around Z axis (millirad /sec) + X Magnetic field (milli tesla) + Y Magnetic field (milli tesla) + Z Magnetic field (milli tesla) + + + The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + X acceleration (raw) + Y acceleration (raw) + Z acceleration (raw) + Angular speed around X axis (raw) + Angular speed around Y axis (raw) + Angular speed around Z axis (raw) + X Magnetic field (raw) + Y Magnetic field (raw) + Z Magnetic field (raw) + + + The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (raw) + Differential pressure 1 (raw) + Differential pressure 2 (raw) + Raw Temperature measurement (raw) + + + The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right). + Timestamp (milliseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. + Timestamp (milliseconds since system boot) + Quaternion component 1 + Quaternion component 2 + Quaternion component 3 + Quaternion component 4 + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + + + The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention) + Timestamp (milliseconds since system boot) + X Position + Y Position + Z Position + X Speed + Y Speed + Z Speed + + + The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient. + Timestamp (milliseconds since system boot) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters), above MSL + Altitude above ground in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + + The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000 + Timestamp (milliseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + Receive signal strength indicator, 0: 0%, 255: 100% + + + The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. + Timestamp (since UNIX epoch or microseconds since system boot) + Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. + Servo output 1 value, in microseconds + Servo output 2 value, in microseconds + Servo output 3 value, in microseconds + Servo output 4 value, in microseconds + Servo output 5 value, in microseconds + Servo output 6 value, in microseconds + Servo output 7 value, in microseconds + Servo output 8 value, in microseconds + + + Message encoding a MISSION. This message is emitted to announce + the presence of a MISSION and to set a MISSION on the system. The MISSION can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed + + System ID + Component ID + Sequence + The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h + The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs + false:0, true:1 + autocontinue to next wp + PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters + PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. + PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH + PARAM5 / local: x position, global: latitude + PARAM6 / y position: global: longitude + PARAM7 / z position: global: altitude + + + Request the information of the MISSION with the sequence number seq. The response of the system to this message should be a MISSION message. + System ID + Component ID + Sequence + + + Set the MISSION with sequence number seq as current MISSION. This means that the MAV will continue to this MISSION on the shortest path (not following the MISSIONs in-between). + System ID + Component ID + Sequence + + + Message that announces the sequence number of the current active MISSION. The MAV will fly towards this MISSION. + Sequence + + + Request the overall list of MISSIONs from the system/component. + System ID + Component ID + + + This message is emitted as response to MISSION_REQUEST_LIST by the MAV. The GCS can then request the individual MISSIONs based on the knowledge of the total number of MISSIONs. + System ID + Component ID + Number of MISSIONs in the Sequence + + + Delete all mission items at once. + System ID + Component ID + + + A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION. + Sequence + + + Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero). + System ID + Component ID + 0: OK, 1: generic error / not accepting mission commands at all right now, 2: coordinate frame is not supported, 3: command is not supported, 4: mission item exceeds storage space, 5: one of the parameters has an invalid value, 6: param1 has an invalid value, 7: param2 has an invalid value, 8: param3 has an invalid value, 9: param4 has an invalid value, 10: x/param5 has an invalid value, 11: y:param6 has an invalid value, 12: z:param7 has an invalid value, 13: received waypoint out of sequence, 14: not accepting any mission commands from this communication partner + + + As local MISSIONs exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor. + System ID + global position * 1E7 + global position * 1E7 + global position * 1000 + + + Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position + Latitude (WGS84), expressed as * 1E7 + Longitude (WGS84), expressed as * 1E7 + Altitude(WGS84), expressed as * 1000 + + + Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/MISSION planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message. + System ID + Component ID + Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + x position + y position + z position + Desired yaw angle + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU + x position + y position + z position + Desired yaw angle + + + Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS. + Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + WGS84 Latitude position in degrees * 1E7 + WGS84 Longitude position in degrees * 1E7 + WGS84 Altitude in meters * 1000 (positive for up) + Desired yaw angle in degrees * 100 + + + Set the current global position setpoint. + Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT + WGS84 Latitude position in degrees * 1E7 + WGS84 Longitude position in degrees * 1E7 + WGS84 Altitude in meters * 1000 (positive for up) + Desired yaw angle in degrees * 100 + + + Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations. + System ID + Component ID + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Read out the safety zone the MAV currently assumes. + Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. + x position 1 / Latitude 1 + y position 1 / Longitude 1 + z position 1 / Altitude 1 + x position 2 / Latitude 2 + y position 2 / Longitude 2 + z position 2 / Altitude 2 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Set roll, pitch and yaw. + System ID + Component ID + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Setpoint in roll, pitch, yaw currently active on the system. + Timestamp in milliseconds since system boot + Desired roll angle in radians + Desired pitch angle in radians + Desired yaw angle in radians + Collective thrust, normalized to 0 .. 1 + + + Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system. + Timestamp in milliseconds since system boot + Desired roll angular speed in rad/s + Desired pitch angular speed in rad/s + Desired yaw angular speed in rad/s + Collective thrust, normalized to 0 .. 1 + + + Outputs of the APM navigation controller. The primary use of this message is to check the response and signs + of the controller before actual flight and to assist with tuning controller parameters + + Current desired roll in degrees + Current desired pitch in degrees + Current desired heading in degrees + Bearing to current MISSION/target in degrees + Distance to active MISSION in meters + Current altitude error in meters + Current airspeed error in meters/second + Current crosstrack error on x-y plane in meters + + + Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. + x position error + y position error + z position error + roll error (radians) + pitch error (radians) + yaw error (radians) + x velocity + y velocity + z velocity + + + The target requested to send the message stream. + The target requested to send the message stream. + The ID of the requested data stream + The requested interval between two messages of this type + 1 to start sending, 0 to stop sending. + + + The ID of the requested data stream + The requested interval between two messages of this type + 1 stream is enabled, 0 stream is stopped. + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + System ID + Component ID + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + + + Metrics typically displayed on a HUD for fixed wing aircraft + Current airspeed in m/s + Current ground speed in m/s + Current heading in degrees, in compass units (0..360, 0=north) + Current throttle setting in integer percent, 0 to 100 + Current altitude (MSL), in meters + Current climb rate in meters/second + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + + + Send a command with up to four parameters to the MAV + System which should execute the command + Component which should execute the command, 0 for all components + Command ID, as defined by MAV_CMD enum. + 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + Parameter 1, as defined by MAV_CMD enum. + Parameter 2, as defined by MAV_CMD enum. + Parameter 3, as defined by MAV_CMD enum. + Parameter 4, as defined by MAV_CMD enum. + Parameter 5, as defined by MAV_CMD enum. + Parameter 6, as defined by MAV_CMD enum. + Parameter 7, as defined by MAV_CMD enum. + + + Report status of a command. Includes feedback wether the command was executed + Command ID, as defined by MAV_CMD enum. + 1: Command ACCEPTED and EXECUTED, 1: Command TEMPORARY REJECTED/DENIED, 2: Command PERMANENTLY DENIED, 3: Command UNKNOWN/UNSUPPORTED, 4: Command executed, but failed + + + + + Sent from simulation to autopilot. This packet is useful for high throughput + applications such as hardware in the loop simulations. + + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Roll angle (rad) + Pitch angle (rad) + Yaw angle (rad) + Roll angular speed (rad/s) + Pitch angular speed (rad/s) + Yaw angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + + + Sent from autopilot to simulation. Hardware in the loop control outputs + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Control output -1 .. 1 + Control output -1 .. 1 + Control output -1 .. 1 + Throttle 0 .. 1 + Aux 1, -1 .. 1 + Aux 2, -1 .. 1 + Aux 3, -1 .. 1 + Aux 4, -1 .. 1 + System mode (MAV_MODE) + Navigation mode (MAV_NAV_MODE) + + + Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + RC channel 1 value, in microseconds + RC channel 2 value, in microseconds + RC channel 3 value, in microseconds + RC channel 4 value, in microseconds + RC channel 5 value, in microseconds + RC channel 6 value, in microseconds + RC channel 7 value, in microseconds + RC channel 8 value, in microseconds + RC channel 9 value, in microseconds + RC channel 10 value, in microseconds + RC channel 11 value, in microseconds + RC channel 12 value, in microseconds + Receive signal strength indicator, 0: 0%, 255: 100% + + + Optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels in x-sensor direction + Flow in pixels in y-sensor direction + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + Timestamp (milliseconds) + Global X speed + Global Y speed + Global Z speed + + + Timestamp (milliseconds) + Global X position + Global Y position + Global Z position + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + + + + Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Starting address of the debug variables + Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below + Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 + Memory contents at specified address + + + Name + Timestamp + x + y + z + + + Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Floating point value + + + Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output. + Timestamp (milliseconds since system boot) + Name of the debug variable + Signed integer value + + + Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz). + Severity of status, 0 = info message, 255 = critical fault + Status text message, without null termination character + + + Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N. + Timestamp (milliseconds since system boot) + index of debug variable + DEBUG value + + + Extended message spacer. + System which should execute the command + Component which should execute the command, 0 for all components + Retransmission / ACK flags + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml new file mode 100644 index 0000000000..185a657de9 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml @@ -0,0 +1,16 @@ + + + 2 + + + + The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot). + Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + Autopilot type / class. defined in MAV_CLASS ENUM + System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. + System status flag, see MAV_STATUS ENUM + MAVLink version + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml new file mode 100644 index 0000000000..2860c2a59a --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml @@ -0,0 +1,203 @@ + + + common.xml + + + Content Types for data transmission handshake + + + + + + + + Camera id + Camera mode: 0 = auto, 1 = manual + Trigger pin, 0-3 for PtGrey FireFly + Shutter interval, in microseconds + Exposure time, in microseconds + Camera gain + + + Timestamp + IMU seq + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + 0 to disable, 1 to enable + + + Camera id + Camera # (starts with 0) + Timestamp + Until which timestamp this buffer will stay valid + The image sequence number + Position of the image in the buffer, starts with 0 + Image width + Image height + Image depth + Image channels + Shared memory area key + Exposure time, in microseconds + Camera gain + Roll angle in rad + Pitch angle in rad + Yaw angle in rad + Local frame Z coordinate (height over ground) + GPS X coordinate + GPS Y coordinate + Global frame altitude + Ground truth X + Ground truth Y + Ground truth Z + + + Message sent to the MAV to set a new position as reference for the controller + System ID + Component ID + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + Message sent to the MAV to set a new offset from the currently controlled position + System ID + Component ID + x position offset + y position offset + z position offset + yaw orientation offset in radians, 0 = NORTH + + + + ID of waypoint, 0 for plain position + x position + y position + z position + yaw orientation in radians, 0 = NORTH + + + ID + x position + y position + z position + roll orientation + pitch orientation + yaw orientation + + + ADC1 (J405 ADC3, LPC2148 AD0.6) + ADC2 (J405 ADC5, LPC2148 AD0.2) + ADC3 (J405 ADC6, LPC2148 AD0.1) + ADC4 (J405 ADC7, LPC2148 AD1.3) + Battery voltage + Temperature (degrees celcius) + Barometric pressure (hecto Pascal) + + + Watchdog ID + Number of processes + + + Watchdog ID + Process ID + Process name + Process arguments + Timeout (seconds) + + + Watchdog ID + Process ID + Is running / finished / suspended / crashed + Is muted + PID + Number of crashes + + + Target system ID + Watchdog ID + Process ID + Command ID + + + 0: Pattern, 1: Letter + Confidence of detection + Pattern file name + Accepted as true detection, 0 no, 1 yes + + + Notifies the operator about a point of interest (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X Position + Y Position + Z Position + POI name + + + Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + + 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug + 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta + 0: global, 1:local + 0: no timeout, >1: timeout in seconds + X1 Position + Y1 Position + Z1 Position + X2 Position + Y2 Position + Z2 Position + POI connection name + + + type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) + total data size in bytes (set on ACK only) + number of packets beeing sent (set on ACK only) + payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) + JPEG quality out of [1,100] + + + sequence number (starting with 0 on every transmission) + image data bytes + + + x position in m + y position in m + z position in m + Orientation assignment 0: false, 1:true + Size in pixels + Orientation + Descriptor + Harris operator response at this location + + + The system to be controlled + roll + pitch + yaw + thrust + roll control enabled auto:0, manual:1 + pitch auto:0, manual:1 + yaw auto:0, manual:1 + thrust auto:0, manual:1 + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml new file mode 100644 index 0000000000..f8644c5c4b --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml @@ -0,0 +1,144 @@ + + + common.xml + + + + + + + Sensor and DSC control loads. + Sensor DSC Load + Control DSC Load + Battery Voltage in millivolts + + + + Air data for altitude and airspeed computation. + Dynamic pressure (Pa) + Static pressure (Pa) + Board temperature + + + + Accelerometer and gyro biases. + Accelerometer X bias (m/s) + Accelerometer Y bias (m/s) + Accelerometer Z bias (m/s) + Gyro X bias (rad/s) + Gyro Y bias (rad/s) + Gyro Z bias (rad/s) + + + + Configurable diagnostic messages. + Diagnostic float 1 + Diagnostic float 2 + Diagnostic float 3 + Diagnostic short 1 + Diagnostic short 2 + Diagnostic short 3 + + + + Data used in the navigation algorithm. + Measured Airspeed prior to the Nav Filter + Commanded Roll + Commanded Pitch + Commanded Turn rate + Y component of the body acceleration + Total Distance to Run on this leg of Navigation + Remaining distance to Run on this leg of Navigation + Origin WP + Destination WP + + + + Configurable data log probes to be used inside Simulink + Log value 1 + Log value 2 + Log value 3 + Log value 4 + Log value 5 + Log value 6 + + + + Pilot console PWM messges. + Year reported by Gps + Month reported by Gps + Day reported by Gps + Hour reported by Gps + Min reported by Gps + Sec reported by Gps + Visible sattelites reported by Gps + + + + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + The system setting the commands + Commanded Airspeed + Log value 2 + Log value 3 + + + + + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + The system setting the commands + Bitfield containing the PT configuration + + + + + + Action messages focused on the SLUGS AP. + The system reporting the action + Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names + Value associated with the action + + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml new file mode 100644 index 0000000000..02bc03204d --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml @@ -0,0 +1,31 @@ + + + 3 + + + Test all field types + char + string + uint8_t + uint16_t + uint32_t + uint64_t + int8_t + int16_t + int32_t + int64_t + float + double + uint8_t_array + uint16_t_array + uint32_t_array + uint64_t_array + int8_t_array + int16_t_array + int32_t_array + int64_t_array + float_array + double_array + + + diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml new file mode 100644 index 0000000000..5e53e141e9 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml @@ -0,0 +1,54 @@ + + + common.xml + + + Available autopilot modes for ualberta uav + Raw input pulse widts sent to output + Inputs are normalized using calibration, the converted back to raw pulse widths for output + dfsdfs + dfsfds + dfsdfsdfs + + + Navigation filter mode + + AHRS mode + INS/GPS initialization mode + INS/GPS mode + + + Mode currently commanded by pilot + sdf + dfs + Rotomotion mode + + + + + Accelerometer and Gyro biases from the navigation filter + Timestamp (microseconds) + b_f[0] + b_f[1] + b_f[2] + b_f[0] + b_f[1] + b_f[2] + + + Complete set of calibration parameters for the radio + Aileron setpoints: left, center, right + Elevator setpoints: nose down, center, nose up + Rudder setpoints: nose left, center, nose right + Tail gyro mode/gain setpoints: heading hold, rate mode + Pitch curve setpoints (every 25%) + Throttle curve setpoints (every 25%) + + + System status specific to ualberta uav + System mode, see UALBERTA_AUTOPILOT_MODE ENUM + Navigation mode, see UALBERTA_NAV_MODE ENUM + Pilot mode, see UALBERTA_PILOT_MODE + + +